final

Dependencies:   MatrixMath Matrix ExperimentServer QEI_pmw MotorShield

Committer:
saloutos
Date:
Thu Oct 01 13:54:16 2020 +0000
Revision:
27:5d60c6ab6d0a
Parent:
26:5822d4d8dca7
Child:
28:22530fdc149b
Notation changes

Who changed what in which revision?

UserRevisionLine numberNew contents of line
pwensing 0:43448bf056e8 1 #include "mbed.h"
pwensing 0:43448bf056e8 2 #include "rtos.h"
pwensing 0:43448bf056e8 3 #include "EthernetInterface.h"
pwensing 0:43448bf056e8 4 #include "ExperimentServer.h"
pwensing 0:43448bf056e8 5 #include "QEI.h"
saloutos 16:f9ea2b2d410f 6 #include "BezierCurve.h"
elijahsj 6:1faceb53dabe 7 #include "MotorShield.h"
elijahsj 13:3a1f4e09789b 8 #include "HardwareSetup.h"
saloutos 26:5822d4d8dca7 9 #include "Matrix.h"
saloutos 26:5822d4d8dca7 10 #include "MatrixMath.h"
pwensing 0:43448bf056e8 11
saloutos 16:f9ea2b2d410f 12 #define BEZIER_ORDER_FOOT 7
saloutos 17:1bb5aa45826e 13 #define NUM_INPUTS (12 + 2*(BEZIER_ORDER_FOOT+1))
saloutos 16:f9ea2b2d410f 14 #define NUM_OUTPUTS 19
pwensing 0:43448bf056e8 15
saloutos 16:f9ea2b2d410f 16 #define PULSE_TO_RAD (2.0f*3.14159f / 1200.0f)
saloutos 16:f9ea2b2d410f 17
saloutos 16:f9ea2b2d410f 18 // Initializations
pwensing 0:43448bf056e8 19 Serial pc(USBTX, USBRX); // USB Serial Terminal
pwensing 0:43448bf056e8 20 ExperimentServer server; // Object that lets us communicate with MATLAB
elijahsj 5:1ab9b2527794 21 Timer t; // Timer to measure elapsed time of experiment
elijahsj 5:1ab9b2527794 22
elijahsj 5:1ab9b2527794 23 QEI encoderA(PE_9,PE_11, NC, 1200, QEI::X4_ENCODING); // MOTOR A ENCODER (no index, 1200 counts/rev, Quadrature encoding)
elijahsj 5:1ab9b2527794 24 QEI encoderB(PA_5, PB_3, NC, 1200, QEI::X4_ENCODING); // MOTOR B ENCODER (no index, 1200 counts/rev, Quadrature encoding)
elijahsj 5:1ab9b2527794 25 QEI encoderC(PC_6, PC_7, NC, 1200, QEI::X4_ENCODING); // MOTOR C ENCODER (no index, 1200 counts/rev, Quadrature encoding)
elijahsj 5:1ab9b2527794 26 QEI encoderD(PD_12, PD_13, NC, 1200, QEI::X4_ENCODING);// MOTOR D ENCODER (no index, 1200 counts/rev, Quadrature encoding)
elijahsj 5:1ab9b2527794 27
elijahsj 12:84a6dcb60422 28 MotorShield motorShield(12000); //initialize the motor shield with a period of 12000 ticks or ~20kHZ
saloutos 16:f9ea2b2d410f 29 Ticker currentLoop;
saloutos 16:f9ea2b2d410f 30
saloutos 26:5822d4d8dca7 31 Matrix MassMatrix(2,2);
saloutos 26:5822d4d8dca7 32 Matrix Jacobian(2,2);
saloutos 26:5822d4d8dca7 33 Matrix JacobianT(2,2);
saloutos 26:5822d4d8dca7 34 Matrix InverseMassMatrix(2,2);
saloutos 26:5822d4d8dca7 35 Matrix temp_product(2,2);
saloutos 26:5822d4d8dca7 36 Matrix Lambda(2,2);
saloutos 26:5822d4d8dca7 37
saloutos 16:f9ea2b2d410f 38 // Variables for q1
saloutos 16:f9ea2b2d410f 39 float current1;
saloutos 16:f9ea2b2d410f 40 float current_des1 = 0;
saloutos 16:f9ea2b2d410f 41 float prev_current_des1 = 0;
saloutos 16:f9ea2b2d410f 42 float current_int1 = 0;
saloutos 16:f9ea2b2d410f 43 float angle1;
saloutos 16:f9ea2b2d410f 44 float velocity1;
saloutos 16:f9ea2b2d410f 45 float duty_cycle1;
saloutos 16:f9ea2b2d410f 46 float angle1_init;
saloutos 16:f9ea2b2d410f 47
saloutos 16:f9ea2b2d410f 48 // Variables for q2
saloutos 16:f9ea2b2d410f 49 float current2;
saloutos 16:f9ea2b2d410f 50 float current_des2 = 0;
saloutos 16:f9ea2b2d410f 51 float prev_current_des2 = 0;
saloutos 16:f9ea2b2d410f 52 float current_int2 = 0;
saloutos 16:f9ea2b2d410f 53 float angle2;
saloutos 16:f9ea2b2d410f 54 float velocity2;
saloutos 16:f9ea2b2d410f 55 float duty_cycle2;
saloutos 16:f9ea2b2d410f 56 float angle2_init;
saloutos 16:f9ea2b2d410f 57
saloutos 16:f9ea2b2d410f 58 // Fixed kinematic parameters
saloutos 16:f9ea2b2d410f 59 const float l_OA=.011;
saloutos 16:f9ea2b2d410f 60 const float l_OB=.042;
saloutos 16:f9ea2b2d410f 61 const float l_AC=.096;
saloutos 16:f9ea2b2d410f 62 const float l_DE=.091;
saloutos 26:5822d4d8dca7 63 const float m1 =.0393 + .2;
saloutos 26:5822d4d8dca7 64 const float m2 =.0368;
saloutos 26:5822d4d8dca7 65 const float m3 = .00783;
saloutos 26:5822d4d8dca7 66 const float m4 = .0155;
saloutos 26:5822d4d8dca7 67 const float I1 = 0.0000251; //25.1 * 10^-6;
saloutos 26:5822d4d8dca7 68 const float I2 = 0.0000535; //53.5 * 10^-6;
saloutos 26:5822d4d8dca7 69 const float I3 = 0.00000925; //9.25 * 10^-6;
saloutos 26:5822d4d8dca7 70 const float I4 = 0.0000222; //22.176 * 10^-6;
saloutos 26:5822d4d8dca7 71 const float l_O_m1=0.032;
saloutos 26:5822d4d8dca7 72 const float l_B_m2=0.0344;
saloutos 26:5822d4d8dca7 73 const float l_A_m3=0.0622;
saloutos 26:5822d4d8dca7 74 const float l_C_m4=0.0610;
saloutos 27:5d60c6ab6d0a 75 const float N = 18.75;
saloutos 27:5d60c6ab6d0a 76 const float Ir = 0.0035/pow(N,2);
saloutos 16:f9ea2b2d410f 77
saloutos 16:f9ea2b2d410f 78 // Timing parameters
saloutos 16:f9ea2b2d410f 79 float current_control_period_us = 200.0f; // 5kHz current control loop
saloutos 16:f9ea2b2d410f 80 float impedance_control_period_us = 1000.0f; // 1kHz impedance control loop
saloutos 16:f9ea2b2d410f 81 float start_period, traj_period, end_period;
saloutos 16:f9ea2b2d410f 82
saloutos 16:f9ea2b2d410f 83 // Control parameters
saloutos 19:562c08086d71 84 float current_Kp = 4.0f;
saloutos 19:562c08086d71 85 float current_Ki = 0.4f;
saloutos 19:562c08086d71 86 float current_int_max = 3.0f;
saloutos 16:f9ea2b2d410f 87 float duty_max;
saloutos 16:f9ea2b2d410f 88 float K_xx;
saloutos 16:f9ea2b2d410f 89 float K_yy;
saloutos 16:f9ea2b2d410f 90 float K_xy;
saloutos 16:f9ea2b2d410f 91 float D_xx;
saloutos 16:f9ea2b2d410f 92 float D_xy;
saloutos 16:f9ea2b2d410f 93 float D_yy;
saloutos 16:f9ea2b2d410f 94
saloutos 16:f9ea2b2d410f 95 // Model parameters
saloutos 17:1bb5aa45826e 96 float supply_voltage = 12; // motor supply voltage
saloutos 18:21c8d94eddee 97 float R = 2.0f; // motor resistance
saloutos 18:21c8d94eddee 98 float k_t = 0.18f; // motor torque constant
saloutos 17:1bb5aa45826e 99 float nu = 0.0005; // motor viscous friction
saloutos 16:f9ea2b2d410f 100
saloutos 16:f9ea2b2d410f 101 // Current control interrupt function
saloutos 16:f9ea2b2d410f 102 void CurrentLoop()
saloutos 16:f9ea2b2d410f 103 {
saloutos 19:562c08086d71 104 // This loop sets the motor voltage commands using PI current controllers with feedforward terms.
saloutos 16:f9ea2b2d410f 105
saloutos 16:f9ea2b2d410f 106 //use the motor shield as follows:
saloutos 16:f9ea2b2d410f 107 //motorShield.motorAWrite(DUTY CYCLE, DIRECTION), DIRECTION = 0 is forward, DIRECTION =1 is backwards.
saloutos 16:f9ea2b2d410f 108
saloutos 18:21c8d94eddee 109 current1 = -(((float(motorShield.readCurrentA())/65536.0f)*30.0f)-15.0f); // measure current
saloutos 18:21c8d94eddee 110 velocity1 = encoderA.getVelocity() * PULSE_TO_RAD; // measure velocity
saloutos 18:21c8d94eddee 111 float err_c1 = current_des1 - current1; // current errror
saloutos 18:21c8d94eddee 112 current_int1 += err_c1; // integrate error
saloutos 18:21c8d94eddee 113 current_int1 = fmaxf( fminf(current_int1, current_int_max), -current_int_max); // anti-windup
saloutos 18:21c8d94eddee 114 float ff1 = R*current_des1 + k_t*velocity1; // feedforward terms
saloutos 18:21c8d94eddee 115 duty_cycle1 = (ff1 + current_Kp*err_c1 + current_Ki*current_int1)/supply_voltage; // PI current controller
saloutos 16:f9ea2b2d410f 116
saloutos 16:f9ea2b2d410f 117 float absDuty1 = abs(duty_cycle1);
saloutos 16:f9ea2b2d410f 118 if (absDuty1 > duty_max) {
saloutos 16:f9ea2b2d410f 119 duty_cycle1 *= duty_max / absDuty1;
saloutos 16:f9ea2b2d410f 120 absDuty1 = duty_max;
saloutos 16:f9ea2b2d410f 121 }
saloutos 16:f9ea2b2d410f 122 if (duty_cycle1 < 0) { // backwards
saloutos 16:f9ea2b2d410f 123 motorShield.motorAWrite(absDuty1, 1);
saloutos 16:f9ea2b2d410f 124 } else { // forwards
saloutos 16:f9ea2b2d410f 125 motorShield.motorAWrite(absDuty1, 0);
saloutos 16:f9ea2b2d410f 126 }
saloutos 16:f9ea2b2d410f 127 prev_current_des1 = current_des1;
saloutos 16:f9ea2b2d410f 128
saloutos 18:21c8d94eddee 129 current2 = -(((float(motorShield.readCurrentB())/65536.0f)*30.0f)-15.0f); // measure current
saloutos 18:21c8d94eddee 130 velocity2 = encoderB.getVelocity() * PULSE_TO_RAD; // measure velocity
saloutos 18:21c8d94eddee 131 float err_c2 = current_des2 - current2; // current error
saloutos 18:21c8d94eddee 132 current_int2 += err_c2; // integrate error
saloutos 18:21c8d94eddee 133 current_int2 = fmaxf( fminf(current_int2, current_int_max), -current_int_max); // anti-windup
saloutos 18:21c8d94eddee 134 float ff2 = R*current_des2 + k_t*velocity2; // feedforward terms
saloutos 18:21c8d94eddee 135 duty_cycle2 = (ff2 + current_Kp*err_c2 + current_Ki*current_int2)/supply_voltage; // PI current controller
saloutos 16:f9ea2b2d410f 136
saloutos 16:f9ea2b2d410f 137 float absDuty2 = abs(duty_cycle2);
saloutos 16:f9ea2b2d410f 138 if (absDuty2 > duty_max) {
saloutos 16:f9ea2b2d410f 139 duty_cycle2 *= duty_max / absDuty2;
saloutos 16:f9ea2b2d410f 140 absDuty2 = duty_max;
saloutos 16:f9ea2b2d410f 141 }
saloutos 16:f9ea2b2d410f 142 if (duty_cycle2 < 0) { // backwards
saloutos 16:f9ea2b2d410f 143 motorShield.motorBWrite(absDuty2, 1);
saloutos 16:f9ea2b2d410f 144 } else { // forwards
saloutos 16:f9ea2b2d410f 145 motorShield.motorBWrite(absDuty2, 0);
saloutos 16:f9ea2b2d410f 146 }
saloutos 16:f9ea2b2d410f 147 prev_current_des2 = current_des2;
saloutos 16:f9ea2b2d410f 148
saloutos 16:f9ea2b2d410f 149 }
elijahsj 6:1faceb53dabe 150
elijahsj 4:7a1b35f081bb 151 int main (void)
elijahsj 4:7a1b35f081bb 152 {
saloutos 17:1bb5aa45826e 153
saloutos 17:1bb5aa45826e 154 // Object for 7th order Cartesian foot trajectory
saloutos 17:1bb5aa45826e 155 BezierCurve rDesFoot_bez(2,BEZIER_ORDER_FOOT);
saloutos 17:1bb5aa45826e 156
pwensing 0:43448bf056e8 157 // Link the terminal with our server and start it up
pwensing 0:43448bf056e8 158 server.attachTerminal(pc);
pwensing 0:43448bf056e8 159 server.init();
elijahsj 13:3a1f4e09789b 160
pwensing 0:43448bf056e8 161 // Continually get input from MATLAB and run experiments
pwensing 0:43448bf056e8 162 float input_params[NUM_INPUTS];
elijahsj 5:1ab9b2527794 163 pc.printf("%f",input_params[0]);
elijahsj 5:1ab9b2527794 164
pwensing 0:43448bf056e8 165 while(1) {
saloutos 16:f9ea2b2d410f 166
saloutos 16:f9ea2b2d410f 167 // If there are new inputs, this code will run
pwensing 0:43448bf056e8 168 if (server.getParams(input_params,NUM_INPUTS)) {
saloutos 16:f9ea2b2d410f 169
saloutos 16:f9ea2b2d410f 170
saloutos 17:1bb5aa45826e 171 // Get inputs from MATLAB
saloutos 16:f9ea2b2d410f 172 start_period = input_params[0]; // First buffer time, before trajectory
saloutos 16:f9ea2b2d410f 173 traj_period = input_params[1]; // Trajectory time/length
saloutos 16:f9ea2b2d410f 174 end_period = input_params[2]; // Second buffer time, after trajectory
saloutos 16:f9ea2b2d410f 175
saloutos 16:f9ea2b2d410f 176 angle1_init = input_params[3]; // Initial angle for q1 (rad)
saloutos 16:f9ea2b2d410f 177 angle2_init = input_params[4]; // Initial angle for q2 (rad)
elijahsj 4:7a1b35f081bb 178
saloutos 16:f9ea2b2d410f 179 K_xx = input_params[5]; // Foot stiffness N/m
saloutos 16:f9ea2b2d410f 180 K_yy = input_params[6]; // Foot stiffness N/m
saloutos 16:f9ea2b2d410f 181 K_xy = input_params[7]; // Foot stiffness N/m
saloutos 16:f9ea2b2d410f 182 D_xx = input_params[8]; // Foot damping N/(m/s)
saloutos 19:562c08086d71 183 D_yy = input_params[9]; // Foot damping N/(m/s)
saloutos 16:f9ea2b2d410f 184 D_xy = input_params[10]; // Foot damping N/(m/s)
saloutos 16:f9ea2b2d410f 185 duty_max = input_params[11]; // Maximum duty factor
saloutos 16:f9ea2b2d410f 186
saloutos 19:562c08086d71 187 // Get foot trajectory points
saloutos 16:f9ea2b2d410f 188 float foot_pts[2*(BEZIER_ORDER_FOOT+1)];
saloutos 16:f9ea2b2d410f 189 for(int i = 0; i<2*(BEZIER_ORDER_FOOT+1);i++) {
saloutos 17:1bb5aa45826e 190 foot_pts[i] = input_params[12+i];
saloutos 16:f9ea2b2d410f 191 }
saloutos 16:f9ea2b2d410f 192 rDesFoot_bez.setPoints(foot_pts);
saloutos 16:f9ea2b2d410f 193
saloutos 16:f9ea2b2d410f 194 // Attach current loop interrupt
saloutos 16:f9ea2b2d410f 195 currentLoop.attach_us(CurrentLoop,current_control_period_us);
saloutos 16:f9ea2b2d410f 196
pwensing 0:43448bf056e8 197 // Setup experiment
pwensing 0:43448bf056e8 198 t.reset();
pwensing 0:43448bf056e8 199 t.start();
elijahsj 5:1ab9b2527794 200 encoderA.reset();
elijahsj 5:1ab9b2527794 201 encoderB.reset();
elijahsj 5:1ab9b2527794 202 encoderC.reset();
elijahsj 5:1ab9b2527794 203 encoderD.reset();
elijahsj 10:a40d180c305c 204
elijahsj 15:495333b2ccf1 205 motorShield.motorAWrite(0, 0); //turn motor A off
saloutos 16:f9ea2b2d410f 206 motorShield.motorBWrite(0, 0); //turn motor B off
saloutos 16:f9ea2b2d410f 207
pwensing 0:43448bf056e8 208 // Run experiment
saloutos 16:f9ea2b2d410f 209 while( t.read() < start_period + traj_period + end_period) {
saloutos 16:f9ea2b2d410f 210
saloutos 19:562c08086d71 211 // Read encoders to get motor states
saloutos 16:f9ea2b2d410f 212 angle1 = encoderA.getPulses() *PULSE_TO_RAD + angle1_init;
saloutos 16:f9ea2b2d410f 213 velocity1 = encoderA.getVelocity() * PULSE_TO_RAD;
saloutos 16:f9ea2b2d410f 214
saloutos 16:f9ea2b2d410f 215 angle2 = encoderB.getPulses() * PULSE_TO_RAD + angle2_init;
saloutos 16:f9ea2b2d410f 216 velocity2 = encoderB.getVelocity() * PULSE_TO_RAD;
saloutos 16:f9ea2b2d410f 217
saloutos 16:f9ea2b2d410f 218 const float th1 = angle1;
saloutos 16:f9ea2b2d410f 219 const float th2 = angle2;
saloutos 16:f9ea2b2d410f 220 const float dth1= velocity1;
saloutos 16:f9ea2b2d410f 221 const float dth2= velocity2;
saloutos 16:f9ea2b2d410f 222
saloutos 16:f9ea2b2d410f 223 // Calculate the Jacobian
saloutos 19:562c08086d71 224 float Jx_th1 = 0;
saloutos 19:562c08086d71 225 float Jx_th2 = 0;
saloutos 19:562c08086d71 226 float Jy_th1 = 0;
saloutos 19:562c08086d71 227 float Jy_th2 = 0;
saloutos 19:562c08086d71 228
saloutos 17:1bb5aa45826e 229 // Calculate the forward kinematics (position and velocity)
saloutos 19:562c08086d71 230 float xFoot = 0;
saloutos 19:562c08086d71 231 float yFoot = 0;
saloutos 19:562c08086d71 232 float dxFoot = 0;
saloutos 19:562c08086d71 233 float dyFoot = 0;
saloutos 16:f9ea2b2d410f 234
saloutos 16:f9ea2b2d410f 235 // Set gains based on buffer and traj times, then calculate desired x,y from Bezier trajectory at current time if necessary
saloutos 16:f9ea2b2d410f 236 float teff = 0;
saloutos 16:f9ea2b2d410f 237 float vMult = 0;
saloutos 16:f9ea2b2d410f 238 if( t < start_period) {
saloutos 16:f9ea2b2d410f 239 if (K_xx > 0 || K_yy > 0) {
saloutos 26:5822d4d8dca7 240 K_xx = 50;
saloutos 26:5822d4d8dca7 241 K_yy = 50;
saloutos 26:5822d4d8dca7 242 D_xx = 2;
saloutos 26:5822d4d8dca7 243 D_yy = 2;
saloutos 16:f9ea2b2d410f 244 K_xy = 0;
saloutos 16:f9ea2b2d410f 245 D_xy = 0;
saloutos 16:f9ea2b2d410f 246 }
saloutos 16:f9ea2b2d410f 247 teff = 0;
saloutos 16:f9ea2b2d410f 248 }
saloutos 16:f9ea2b2d410f 249 else if (t < start_period + traj_period)
saloutos 16:f9ea2b2d410f 250 {
saloutos 19:562c08086d71 251 K_xx = input_params[5]; // Foot stiffness N/m
saloutos 19:562c08086d71 252 K_yy = input_params[6]; // Foot stiffness N/m
saloutos 19:562c08086d71 253 K_xy = input_params[7]; // Foot stiffness N/m
saloutos 19:562c08086d71 254 D_xx = input_params[8]; // Foot damping N/(m/s)
saloutos 19:562c08086d71 255 D_yy = input_params[9]; // Foot damping N/(m/s)
saloutos 16:f9ea2b2d410f 256 D_xy = input_params[10]; // Foot damping N/(m/s)
saloutos 16:f9ea2b2d410f 257 teff = (t-start_period);
saloutos 16:f9ea2b2d410f 258 vMult = 1;
saloutos 16:f9ea2b2d410f 259 }
elijahsj 4:7a1b35f081bb 260 else
saloutos 16:f9ea2b2d410f 261 {
saloutos 17:1bb5aa45826e 262 teff = traj_period;
saloutos 17:1bb5aa45826e 263 vMult = 0;
saloutos 16:f9ea2b2d410f 264 }
saloutos 16:f9ea2b2d410f 265
saloutos 24:26a515ebb7cf 266 // Get desired foot positions and velocities
saloutos 16:f9ea2b2d410f 267 float rDesFoot[2] , vDesFoot[2];
saloutos 16:f9ea2b2d410f 268 rDesFoot_bez.evaluate(teff/traj_period,rDesFoot);
saloutos 16:f9ea2b2d410f 269 rDesFoot_bez.evaluateDerivative(teff/traj_period,vDesFoot);
saloutos 16:f9ea2b2d410f 270 vDesFoot[0]/=traj_period;
saloutos 16:f9ea2b2d410f 271 vDesFoot[1]/=traj_period;
saloutos 16:f9ea2b2d410f 272 vDesFoot[0]*=vMult;
saloutos 16:f9ea2b2d410f 273 vDesFoot[1]*=vMult;
saloutos 17:1bb5aa45826e 274
saloutos 19:562c08086d71 275 // Calculate the inverse kinematics (joint positions and velocities) for desired joint angles
saloutos 24:26a515ebb7cf 276 float xFoot_inv = -rDesFoot[0];
saloutos 24:26a515ebb7cf 277 float yFoot_inv = rDesFoot[1];
saloutos 24:26a515ebb7cf 278 float l_OE = sqrt( (pow(xFoot_inv,2) + pow(yFoot_inv,2)) );
saloutos 17:1bb5aa45826e 279 float alpha = abs(acos( (pow(l_OE,2) - pow(l_AC,2) - pow((l_OB+l_DE),2))/(-2.0f*l_AC*(l_OB+l_DE)) ));
saloutos 18:21c8d94eddee 280 float th2_des = -(3.14159f - alpha);
saloutos 24:26a515ebb7cf 281 float th1_des = -((3.14159f/2.0f) + atan2(yFoot_inv,xFoot_inv) - abs(asin( (l_AC/l_OE)*sin(alpha) )));
saloutos 17:1bb5aa45826e 282
saloutos 17:1bb5aa45826e 283 float dd = (Jx_th1*Jy_th2 - Jx_th2*Jy_th1);
saloutos 17:1bb5aa45826e 284 float dth1_des = (1.0f/dd) * ( Jy_th2*vDesFoot[0] - Jx_th2*vDesFoot[1] );
saloutos 17:1bb5aa45826e 285 float dth2_des = (1.0f/dd) * ( -Jy_th1*vDesFoot[0] + Jx_th1*vDesFoot[1] );
saloutos 17:1bb5aa45826e 286
saloutos 16:f9ea2b2d410f 287 // Calculate error variables
saloutos 19:562c08086d71 288 float e_x = 0;
saloutos 19:562c08086d71 289 float e_y = 0;
saloutos 19:562c08086d71 290 float de_x = 0;
saloutos 19:562c08086d71 291 float de_y = 0;
saloutos 17:1bb5aa45826e 292
saloutos 16:f9ea2b2d410f 293 // Calculate virtual force on foot
saloutos 19:562c08086d71 294 float fx = 0;
saloutos 19:562c08086d71 295 float fy = 0;
saloutos 26:5822d4d8dca7 296
saloutos 26:5822d4d8dca7 297 // Calculate mass matrix elements
saloutos 27:5d60c6ab6d0a 298 float M11 = I1 + I2 + I3 + I4 + Ir + Ir*pow(N,2) + pow(l_AC,2)*m4 + pow(l_A_m3,2)*m3 + pow(l_B_m2,2)*m2 + pow(l_C_m4,2)*m4 + pow(l_OA,2)*m3 + pow(l_OB,2)*m2 + pow(l_OA,2)*m4 + pow(l_O_m1,2)*m1 + 2*l_C_m4*l_OA*m4 + 2*l_AC*l_C_m4*m4*cos(th2) + 2*l_AC*l_OA*m4*cos(th2) + 2*l_A_m3*l_OA*m3*cos(th2) + 2*l_B_m2*l_OB*m2*cos(th2);
saloutos 27:5d60c6ab6d0a 299 float M12 = I2 + I3 + pow(l_AC,2)*m4 + pow(l_A_m3,2)*m3 + pow(l_B_m2,2)*m2 + Ir*N + l_AC*l_C_m4*m4*cos(th2) + l_AC*l_OA*m4*cos(th2) + l_A_m3*l_OA*m3*cos(th2) + l_B_m2*l_OB*m2*cos(th2);
saloutos 27:5d60c6ab6d0a 300 float M22 = Ir*pow(N,2) + m4*pow(l_AC,2) + m3*pow(l_A_m3,2) + m2*pow(l_B_m2,2) + I2 + I3;
saloutos 26:5822d4d8dca7 301
saloutos 26:5822d4d8dca7 302 // Populate mass matrix
saloutos 26:5822d4d8dca7 303 MassMatrix.Clear();
saloutos 26:5822d4d8dca7 304 MassMatrix << M11 << M12
saloutos 26:5822d4d8dca7 305 << M12 << M22;
saloutos 26:5822d4d8dca7 306
saloutos 26:5822d4d8dca7 307 // Populate Jacobian matrix
saloutos 26:5822d4d8dca7 308 Jacobian.Clear();
saloutos 26:5822d4d8dca7 309 Jacobian << Jx_th1 << Jx_th2
saloutos 26:5822d4d8dca7 310 << Jy_th1 << Jy_th2;
saloutos 26:5822d4d8dca7 311
saloutos 26:5822d4d8dca7 312 // Calculate Lambda matrix
saloutos 26:5822d4d8dca7 313 JacobianT = MatrixMath::Transpose(Jacobian);
saloutos 26:5822d4d8dca7 314 InverseMassMatrix = MatrixMath::Inv(MassMatrix);
saloutos 26:5822d4d8dca7 315 temp_product = Jacobian*InverseMassMatrix*JacobianT;
saloutos 26:5822d4d8dca7 316 Lambda = MatrixMath::Inv(temp_product);
saloutos 26:5822d4d8dca7 317
saloutos 26:5822d4d8dca7 318 // Pull elements of Lambda matrix
saloutos 26:5822d4d8dca7 319 float L11 = Lambda.getNumber(1,1);
saloutos 26:5822d4d8dca7 320 float L12 = Lambda.getNumber(1,2);
saloutos 26:5822d4d8dca7 321 float L21 = Lambda.getNumber(2,1);
saloutos 26:5822d4d8dca7 322 float L22 = Lambda.getNumber(2,2);
saloutos 18:21c8d94eddee 323
saloutos 19:562c08086d71 324 // Set desired currents
saloutos 19:562c08086d71 325 current_des1 = 0;
saloutos 19:562c08086d71 326 current_des2 = 0;
saloutos 26:5822d4d8dca7 327
saloutos 26:5822d4d8dca7 328
saloutos 26:5822d4d8dca7 329
saloutos 16:f9ea2b2d410f 330
saloutos 19:562c08086d71 331
saloutos 19:562c08086d71 332 // Form output to send to MATLAB
saloutos 16:f9ea2b2d410f 333 float output_data[NUM_OUTPUTS];
saloutos 16:f9ea2b2d410f 334 // current time
pwensing 0:43448bf056e8 335 output_data[0] = t.read();
saloutos 16:f9ea2b2d410f 336 // motor 1 state
saloutos 16:f9ea2b2d410f 337 output_data[1] = angle1;
saloutos 16:f9ea2b2d410f 338 output_data[2] = velocity1;
saloutos 16:f9ea2b2d410f 339 output_data[3] = current1;
saloutos 16:f9ea2b2d410f 340 output_data[4] = current_des1;
saloutos 16:f9ea2b2d410f 341 output_data[5] = duty_cycle1;
saloutos 16:f9ea2b2d410f 342 // motor 2 state
saloutos 16:f9ea2b2d410f 343 output_data[6] = angle2;
saloutos 16:f9ea2b2d410f 344 output_data[7] = velocity2;
saloutos 16:f9ea2b2d410f 345 output_data[8] = current2;
saloutos 16:f9ea2b2d410f 346 output_data[9] = current_des2;
saloutos 16:f9ea2b2d410f 347 output_data[10]= duty_cycle2;
saloutos 16:f9ea2b2d410f 348 // foot state
saloutos 16:f9ea2b2d410f 349 output_data[11] = xFoot;
saloutos 16:f9ea2b2d410f 350 output_data[12] = yFoot;
saloutos 17:1bb5aa45826e 351 output_data[13] = dxFoot;
saloutos 17:1bb5aa45826e 352 output_data[14] = dyFoot;
saloutos 17:1bb5aa45826e 353 output_data[15] = rDesFoot[0];
saloutos 17:1bb5aa45826e 354 output_data[16] = rDesFoot[1];
saloutos 17:1bb5aa45826e 355 output_data[17] = vDesFoot[0];
saloutos 17:1bb5aa45826e 356 output_data[18] = vDesFoot[1];
elijahsj 13:3a1f4e09789b 357
pwensing 0:43448bf056e8 358 // Send data to MATLAB
pwensing 0:43448bf056e8 359 server.sendData(output_data,NUM_OUTPUTS);
saloutos 16:f9ea2b2d410f 360
saloutos 16:f9ea2b2d410f 361 wait_us(impedance_control_period_us);
elijahsj 4:7a1b35f081bb 362 }
saloutos 16:f9ea2b2d410f 363
pwensing 0:43448bf056e8 364 // Cleanup after experiment
pwensing 0:43448bf056e8 365 server.setExperimentComplete();
saloutos 16:f9ea2b2d410f 366 currentLoop.detach();
elijahsj 12:84a6dcb60422 367 motorShield.motorAWrite(0, 0); //turn motor A off
saloutos 16:f9ea2b2d410f 368 motorShield.motorBWrite(0, 0); //turn motor B off
saloutos 16:f9ea2b2d410f 369
pwensing 0:43448bf056e8 370 } // end if
saloutos 16:f9ea2b2d410f 371
pwensing 0:43448bf056e8 372 } // end while
elijahsj 10:a40d180c305c 373
elijahsj 6:1faceb53dabe 374 } // end main
elijahsj 6:1faceb53dabe 375