Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: MatrixMath Matrix ExperimentServer QEI_pmw MotorShield
main.cpp@32:c60a5d33cd79, 2020-11-02 (annotated)
- Committer:
- suribe
- Date:
- Mon Nov 02 21:26:44 2020 +0000
- Revision:
- 32:c60a5d33cd79
- Parent:
- 31:4424902a0fd0
- Child:
- 34:9a24d0f718ac
k
Who changed what in which revision?
| User | Revision | Line number | New 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 | |
| suribe | 32:c60a5d33cd79 | 58 | |
| saloutos | 16:f9ea2b2d410f | 59 | |
| saloutos | 16:f9ea2b2d410f | 60 | // Timing parameters |
| saloutos | 16:f9ea2b2d410f | 61 | float current_control_period_us = 200.0f; // 5kHz current control loop |
| saloutos | 16:f9ea2b2d410f | 62 | float impedance_control_period_us = 1000.0f; // 1kHz impedance control loop |
| saloutos | 16:f9ea2b2d410f | 63 | float start_period, traj_period, end_period; |
| saloutos | 16:f9ea2b2d410f | 64 | |
| suribe | 32:c60a5d33cd79 | 65 | // Hardware kinematic parameters -- NEED PAN PARAMETERS |
| suribe | 32:c60a5d33cd79 | 66 | const float l_c1; //upper arm center of mass |
| suribe | 32:c60a5d33cd79 | 67 | const float l_B; //upper arm length |
| suribe | 32:c60a5d33cd79 | 68 | const float r_c2; //lower arm center of mass |
| suribe | 32:c60a5d33cd79 | 69 | const float l_C; //lower arm length |
| suribe | 32:c60a5d33cd79 | 70 | |
| suribe | 32:c60a5d33cd79 | 71 | const float m1; //mass of upper arm |
| suribe | 32:c60a5d33cd79 | 72 | const float m2; //mass of lower arm |
| suribe | 32:c60a5d33cd79 | 73 | |
| suribe | 32:c60a5d33cd79 | 74 | const float I1; //upper arm interia |
| suribe | 32:c60a5d33cd79 | 75 | const float I2; //lower arm inertia |
| suribe | 32:c60a5d33cd79 | 76 | |
| suribe | 32:c60a5d33cd79 | 77 | const float N; //gear ratio |
| suribe | 32:c60a5d33cd79 | 78 | const float Ir; //motor inertia |
| suribe | 32:c60a5d33cd79 | 79 | |
| saloutos | 16:f9ea2b2d410f | 80 | // Control parameters |
| saloutos | 19:562c08086d71 | 81 | float current_Kp = 4.0f; |
| saloutos | 19:562c08086d71 | 82 | float current_Ki = 0.4f; |
| saloutos | 19:562c08086d71 | 83 | float current_int_max = 3.0f; |
| saloutos | 16:f9ea2b2d410f | 84 | float duty_max; |
| saloutos | 16:f9ea2b2d410f | 85 | float K_xx; |
| saloutos | 16:f9ea2b2d410f | 86 | float K_yy; |
| saloutos | 16:f9ea2b2d410f | 87 | float K_xy; |
| saloutos | 16:f9ea2b2d410f | 88 | float D_xx; |
| saloutos | 16:f9ea2b2d410f | 89 | float D_xy; |
| saloutos | 16:f9ea2b2d410f | 90 | float D_yy; |
| saloutos | 16:f9ea2b2d410f | 91 | |
| saloutos | 16:f9ea2b2d410f | 92 | // Model parameters |
| saloutos | 17:1bb5aa45826e | 93 | float supply_voltage = 12; // motor supply voltage |
| saloutos | 18:21c8d94eddee | 94 | float R = 2.0f; // motor resistance |
| saloutos | 18:21c8d94eddee | 95 | float k_t = 0.18f; // motor torque constant |
| saloutos | 17:1bb5aa45826e | 96 | float nu = 0.0005; // motor viscous friction |
| saloutos | 16:f9ea2b2d410f | 97 | |
| saloutos | 16:f9ea2b2d410f | 98 | // Current control interrupt function |
| saloutos | 16:f9ea2b2d410f | 99 | void CurrentLoop() |
| saloutos | 16:f9ea2b2d410f | 100 | { |
| saloutos | 19:562c08086d71 | 101 | // This loop sets the motor voltage commands using PI current controllers with feedforward terms. |
| saloutos | 16:f9ea2b2d410f | 102 | |
| saloutos | 16:f9ea2b2d410f | 103 | //use the motor shield as follows: |
| saloutos | 16:f9ea2b2d410f | 104 | //motorShield.motorAWrite(DUTY CYCLE, DIRECTION), DIRECTION = 0 is forward, DIRECTION =1 is backwards. |
| saloutos | 16:f9ea2b2d410f | 105 | |
| saloutos | 18:21c8d94eddee | 106 | current1 = -(((float(motorShield.readCurrentA())/65536.0f)*30.0f)-15.0f); // measure current |
| saloutos | 18:21c8d94eddee | 107 | velocity1 = encoderA.getVelocity() * PULSE_TO_RAD; // measure velocity |
| saloutos | 18:21c8d94eddee | 108 | float err_c1 = current_des1 - current1; // current errror |
| saloutos | 18:21c8d94eddee | 109 | current_int1 += err_c1; // integrate error |
| saloutos | 18:21c8d94eddee | 110 | current_int1 = fmaxf( fminf(current_int1, current_int_max), -current_int_max); // anti-windup |
| saloutos | 18:21c8d94eddee | 111 | float ff1 = R*current_des1 + k_t*velocity1; // feedforward terms |
| saloutos | 18:21c8d94eddee | 112 | duty_cycle1 = (ff1 + current_Kp*err_c1 + current_Ki*current_int1)/supply_voltage; // PI current controller |
| saloutos | 16:f9ea2b2d410f | 113 | |
| saloutos | 16:f9ea2b2d410f | 114 | float absDuty1 = abs(duty_cycle1); |
| saloutos | 16:f9ea2b2d410f | 115 | if (absDuty1 > duty_max) { |
| saloutos | 16:f9ea2b2d410f | 116 | duty_cycle1 *= duty_max / absDuty1; |
| saloutos | 16:f9ea2b2d410f | 117 | absDuty1 = duty_max; |
| saloutos | 16:f9ea2b2d410f | 118 | } |
| saloutos | 16:f9ea2b2d410f | 119 | if (duty_cycle1 < 0) { // backwards |
| saloutos | 16:f9ea2b2d410f | 120 | motorShield.motorAWrite(absDuty1, 1); |
| saloutos | 16:f9ea2b2d410f | 121 | } else { // forwards |
| saloutos | 16:f9ea2b2d410f | 122 | motorShield.motorAWrite(absDuty1, 0); |
| saloutos | 16:f9ea2b2d410f | 123 | } |
| saloutos | 16:f9ea2b2d410f | 124 | prev_current_des1 = current_des1; |
| saloutos | 16:f9ea2b2d410f | 125 | |
| saloutos | 18:21c8d94eddee | 126 | current2 = -(((float(motorShield.readCurrentB())/65536.0f)*30.0f)-15.0f); // measure current |
| saloutos | 18:21c8d94eddee | 127 | velocity2 = encoderB.getVelocity() * PULSE_TO_RAD; // measure velocity |
| saloutos | 18:21c8d94eddee | 128 | float err_c2 = current_des2 - current2; // current error |
| saloutos | 18:21c8d94eddee | 129 | current_int2 += err_c2; // integrate error |
| saloutos | 18:21c8d94eddee | 130 | current_int2 = fmaxf( fminf(current_int2, current_int_max), -current_int_max); // anti-windup |
| saloutos | 18:21c8d94eddee | 131 | float ff2 = R*current_des2 + k_t*velocity2; // feedforward terms |
| saloutos | 18:21c8d94eddee | 132 | duty_cycle2 = (ff2 + current_Kp*err_c2 + current_Ki*current_int2)/supply_voltage; // PI current controller |
| saloutos | 16:f9ea2b2d410f | 133 | |
| saloutos | 16:f9ea2b2d410f | 134 | float absDuty2 = abs(duty_cycle2); |
| saloutos | 16:f9ea2b2d410f | 135 | if (absDuty2 > duty_max) { |
| saloutos | 16:f9ea2b2d410f | 136 | duty_cycle2 *= duty_max / absDuty2; |
| saloutos | 16:f9ea2b2d410f | 137 | absDuty2 = duty_max; |
| saloutos | 16:f9ea2b2d410f | 138 | } |
| saloutos | 16:f9ea2b2d410f | 139 | if (duty_cycle2 < 0) { // backwards |
| saloutos | 16:f9ea2b2d410f | 140 | motorShield.motorBWrite(absDuty2, 1); |
| saloutos | 16:f9ea2b2d410f | 141 | } else { // forwards |
| saloutos | 16:f9ea2b2d410f | 142 | motorShield.motorBWrite(absDuty2, 0); |
| saloutos | 16:f9ea2b2d410f | 143 | } |
| saloutos | 16:f9ea2b2d410f | 144 | prev_current_des2 = current_des2; |
| saloutos | 16:f9ea2b2d410f | 145 | } |
| elijahsj | 6:1faceb53dabe | 146 | |
| elijahsj | 4:7a1b35f081bb | 147 | int main (void) |
| elijahsj | 4:7a1b35f081bb | 148 | { |
| saloutos | 17:1bb5aa45826e | 149 | // Object for 7th order Cartesian foot trajectory |
| saloutos | 17:1bb5aa45826e | 150 | BezierCurve rDesFoot_bez(2,BEZIER_ORDER_FOOT); |
| saloutos | 17:1bb5aa45826e | 151 | |
| pwensing | 0:43448bf056e8 | 152 | // Link the terminal with our server and start it up |
| pwensing | 0:43448bf056e8 | 153 | server.attachTerminal(pc); |
| pwensing | 0:43448bf056e8 | 154 | server.init(); |
| elijahsj | 13:3a1f4e09789b | 155 | |
| pwensing | 0:43448bf056e8 | 156 | // Continually get input from MATLAB and run experiments |
| pwensing | 0:43448bf056e8 | 157 | float input_params[NUM_INPUTS]; |
| elijahsj | 5:1ab9b2527794 | 158 | pc.printf("%f",input_params[0]); |
| elijahsj | 5:1ab9b2527794 | 159 | |
| pwensing | 0:43448bf056e8 | 160 | while(1) { |
| saloutos | 16:f9ea2b2d410f | 161 | // If there are new inputs, this code will run |
| pwensing | 0:43448bf056e8 | 162 | if (server.getParams(input_params,NUM_INPUTS)) { |
| suribe | 32:c60a5d33cd79 | 163 | // Get inputs from MATLAB |
| suribe | 32:c60a5d33cd79 | 164 | start_period = input_params[0]; // First buffer time, before trajectory |
| suribe | 32:c60a5d33cd79 | 165 | traj_period = input_params[1]; // Trajectory time/length |
| suribe | 32:c60a5d33cd79 | 166 | end_period = input_params[2]; // Second buffer time, after trajectory |
| saloutos | 16:f9ea2b2d410f | 167 | |
| suribe | 32:c60a5d33cd79 | 168 | l_c1 = input_params[3]; //upper arm center of mass |
| suribe | 32:c60a5d33cd79 | 169 | l_B = input_params[4]; //upper arm length |
| suribe | 32:c60a5d33cd79 | 170 | l_c2 = input_params[5]; //lower arm center of mass |
| suribe | 32:c60a5d33cd79 | 171 | l_C = input_params[6]; //lower arm length |
| suribe | 32:c60a5d33cd79 | 172 | |
| suribe | 32:c60a5d33cd79 | 173 | m1 = input_params[7]; //mass of upper arm |
| suribe | 32:c60a5d33cd79 | 174 | m2 = input_params[8]; //mass of lower arm |
| suribe | 32:c60a5d33cd79 | 175 | |
| suribe | 32:c60a5d33cd79 | 176 | I1 = input_params[9]; //upper arm interia |
| suribe | 32:c60a5d33cd79 | 177 | I2 = input_params[10]; //lower arm inertia |
| suribe | 32:c60a5d33cd79 | 178 | |
| suribe | 32:c60a5d33cd79 | 179 | N = input_params[11]; //gear ratio |
| suribe | 32:c60a5d33cd79 | 180 | Ir = input_params[12]; //motor inertia |
| saloutos | 16:f9ea2b2d410f | 181 | |
| suribe | 32:c60a5d33cd79 | 182 | angle1_init = input_params[13]; // Initial angle for q1 (rad) |
| suribe | 32:c60a5d33cd79 | 183 | angle2_init = input_params[14]; // Initial angle for q2 (rad) |
| elijahsj | 4:7a1b35f081bb | 184 | |
| suribe | 32:c60a5d33cd79 | 185 | K_xx = input_params[15]; // Foot stiffness N/m |
| suribe | 32:c60a5d33cd79 | 186 | K_yy = input_params[16]; // Foot stiffness N/m |
| suribe | 32:c60a5d33cd79 | 187 | K_xy = input_params[17]; // Foot stiffness N/m |
| suribe | 32:c60a5d33cd79 | 188 | D_xx = input_params[18]; // Foot damping N/(m/s) |
| suribe | 32:c60a5d33cd79 | 189 | D_yy = input_params[19]; // Foot damping N/(m/s) |
| suribe | 32:c60a5d33cd79 | 190 | D_xy = input_params[20]; // Foot damping N/(m/s) |
| suribe | 32:c60a5d33cd79 | 191 | duty_max = input_params[21]; // Maximum duty factor |
| saloutos | 16:f9ea2b2d410f | 192 | |
| saloutos | 19:562c08086d71 | 193 | // Get foot trajectory points |
| saloutos | 16:f9ea2b2d410f | 194 | float foot_pts[2*(BEZIER_ORDER_FOOT+1)]; |
| saloutos | 16:f9ea2b2d410f | 195 | for(int i = 0; i<2*(BEZIER_ORDER_FOOT+1);i++) { |
| saloutos | 17:1bb5aa45826e | 196 | foot_pts[i] = input_params[12+i]; |
| saloutos | 16:f9ea2b2d410f | 197 | } |
| saloutos | 16:f9ea2b2d410f | 198 | rDesFoot_bez.setPoints(foot_pts); |
| saloutos | 16:f9ea2b2d410f | 199 | |
| saloutos | 16:f9ea2b2d410f | 200 | // Attach current loop interrupt |
| saloutos | 16:f9ea2b2d410f | 201 | currentLoop.attach_us(CurrentLoop,current_control_period_us); |
| saloutos | 16:f9ea2b2d410f | 202 | |
| pwensing | 0:43448bf056e8 | 203 | // Setup experiment |
| pwensing | 0:43448bf056e8 | 204 | t.reset(); |
| pwensing | 0:43448bf056e8 | 205 | t.start(); |
| elijahsj | 5:1ab9b2527794 | 206 | encoderA.reset(); |
| elijahsj | 5:1ab9b2527794 | 207 | encoderB.reset(); |
| elijahsj | 5:1ab9b2527794 | 208 | encoderC.reset(); |
| elijahsj | 5:1ab9b2527794 | 209 | encoderD.reset(); |
| elijahsj | 10:a40d180c305c | 210 | |
| elijahsj | 15:495333b2ccf1 | 211 | motorShield.motorAWrite(0, 0); //turn motor A off |
| saloutos | 16:f9ea2b2d410f | 212 | motorShield.motorBWrite(0, 0); //turn motor B off |
| saloutos | 16:f9ea2b2d410f | 213 | |
| pwensing | 0:43448bf056e8 | 214 | // Run experiment |
| saloutos | 16:f9ea2b2d410f | 215 | while( t.read() < start_period + traj_period + end_period) { |
| saloutos | 16:f9ea2b2d410f | 216 | |
| saloutos | 19:562c08086d71 | 217 | // Read encoders to get motor states |
| saloutos | 16:f9ea2b2d410f | 218 | angle1 = encoderA.getPulses() *PULSE_TO_RAD + angle1_init; |
| saloutos | 16:f9ea2b2d410f | 219 | velocity1 = encoderA.getVelocity() * PULSE_TO_RAD; |
| saloutos | 16:f9ea2b2d410f | 220 | |
| saloutos | 16:f9ea2b2d410f | 221 | angle2 = encoderB.getPulses() * PULSE_TO_RAD + angle2_init; |
| saloutos | 16:f9ea2b2d410f | 222 | velocity2 = encoderB.getVelocity() * PULSE_TO_RAD; |
| saloutos | 16:f9ea2b2d410f | 223 | |
| saloutos | 16:f9ea2b2d410f | 224 | const float th1 = angle1; |
| saloutos | 16:f9ea2b2d410f | 225 | const float th2 = angle2; |
| saloutos | 16:f9ea2b2d410f | 226 | const float dth1= velocity1; |
| saloutos | 16:f9ea2b2d410f | 227 | const float dth2= velocity2; |
| saloutos | 16:f9ea2b2d410f | 228 | |
| saloutos | 16:f9ea2b2d410f | 229 | // Calculate the Jacobian |
| suribe | 29:a88dd750fdbd | 230 | float Jx_th1 = l_AC*cos(th1+th2)+l_DE*cos(th1)+l_OB*cos(th1); |
| suribe | 29:a88dd750fdbd | 231 | float Jx_th2 = l_AC*cos(th1+th2); |
| suribe | 29:a88dd750fdbd | 232 | float Jy_th1 = l_AC*sin(th1+th2)+l_DE*sin(th1)+l_OB*sin(th1); |
| suribe | 29:a88dd750fdbd | 233 | float Jy_th2 = l_AC*sin(th1+th2); |
| saloutos | 19:562c08086d71 | 234 | |
| saloutos | 17:1bb5aa45826e | 235 | // Calculate the forward kinematics (position and velocity) |
| suribe | 29:a88dd750fdbd | 236 | float xFoot = l_DE*sin(th1)+l_OB*sin(th1)+l_AC*sin(th1+th2); |
| suribe | 29:a88dd750fdbd | 237 | float yFoot = -l_DE*cos(th1)-l_OB*cos(th1)-l_AC*cos(th1+th2); |
| suribe | 29:a88dd750fdbd | 238 | float dxFoot = dth1*(l_AC*cos(th1+th2)+l_DE*cos(th1)+l_OB*cos(th1))+dth2*l_AC*cos(th1+th2); |
| suribe | 29:a88dd750fdbd | 239 | float dyFoot = dth1*(l_AC*sin(th1+th2)+l_DE*sin(th1)+l_OB*sin(th1))+dth2*l_AC*sin(th1+th2); |
| suribe | 29:a88dd750fdbd | 240 | |
| saloutos | 16:f9ea2b2d410f | 241 | |
| saloutos | 16:f9ea2b2d410f | 242 | // Set gains based on buffer and traj times, then calculate desired x,y from Bezier trajectory at current time if necessary |
| saloutos | 16:f9ea2b2d410f | 243 | float teff = 0; |
| saloutos | 16:f9ea2b2d410f | 244 | float vMult = 0; |
| saloutos | 16:f9ea2b2d410f | 245 | if( t < start_period) { |
| saloutos | 16:f9ea2b2d410f | 246 | if (K_xx > 0 || K_yy > 0) { |
| saloutos | 28:22530fdc149b | 247 | K_xx = 100; |
| saloutos | 28:22530fdc149b | 248 | K_yy = 100; |
| saloutos | 28:22530fdc149b | 249 | D_xx = 5; |
| saloutos | 28:22530fdc149b | 250 | D_yy = 5; |
| saloutos | 16:f9ea2b2d410f | 251 | K_xy = 0; |
| saloutos | 16:f9ea2b2d410f | 252 | D_xy = 0; |
| saloutos | 16:f9ea2b2d410f | 253 | } |
| saloutos | 16:f9ea2b2d410f | 254 | teff = 0; |
| saloutos | 16:f9ea2b2d410f | 255 | } |
| saloutos | 16:f9ea2b2d410f | 256 | else if (t < start_period + traj_period) |
| saloutos | 16:f9ea2b2d410f | 257 | { |
| suribe | 32:c60a5d33cd79 | 258 | K_xx = input_params[15]; // Foot stiffness N/m |
| suribe | 32:c60a5d33cd79 | 259 | K_yy = input_params[16]; // Foot stiffness N/m |
| suribe | 32:c60a5d33cd79 | 260 | K_xy = input_params[17]; // Foot stiffness N/m |
| suribe | 32:c60a5d33cd79 | 261 | D_xx = input_params[18]; // Foot damping N/(m/s) |
| suribe | 32:c60a5d33cd79 | 262 | D_yy = input_params[19]; // Foot damping N/(m/s) |
| suribe | 32:c60a5d33cd79 | 263 | D_xy = input_params[20]; // Foot damping N/(m/s) |
| saloutos | 16:f9ea2b2d410f | 264 | teff = (t-start_period); |
| saloutos | 16:f9ea2b2d410f | 265 | vMult = 1; |
| saloutos | 16:f9ea2b2d410f | 266 | } |
| elijahsj | 4:7a1b35f081bb | 267 | else |
| saloutos | 16:f9ea2b2d410f | 268 | { |
| saloutos | 17:1bb5aa45826e | 269 | teff = traj_period; |
| saloutos | 17:1bb5aa45826e | 270 | vMult = 0; |
| saloutos | 16:f9ea2b2d410f | 271 | } |
| saloutos | 16:f9ea2b2d410f | 272 | |
| saloutos | 24:26a515ebb7cf | 273 | // Get desired foot positions and velocities |
| saloutos | 16:f9ea2b2d410f | 274 | float rDesFoot[2] , vDesFoot[2]; |
| saloutos | 16:f9ea2b2d410f | 275 | rDesFoot_bez.evaluate(teff/traj_period,rDesFoot); |
| saloutos | 16:f9ea2b2d410f | 276 | rDesFoot_bez.evaluateDerivative(teff/traj_period,vDesFoot); |
| saloutos | 16:f9ea2b2d410f | 277 | vDesFoot[0]/=traj_period; |
| saloutos | 16:f9ea2b2d410f | 278 | vDesFoot[1]/=traj_period; |
| saloutos | 16:f9ea2b2d410f | 279 | vDesFoot[0]*=vMult; |
| saloutos | 16:f9ea2b2d410f | 280 | vDesFoot[1]*=vMult; |
| saloutos | 17:1bb5aa45826e | 281 | |
| saloutos | 19:562c08086d71 | 282 | // Calculate the inverse kinematics (joint positions and velocities) for desired joint angles |
| suribe | 29:a88dd750fdbd | 283 | float xFootd = -rDesFoot[0]; |
| suribe | 29:a88dd750fdbd | 284 | float yFootd = rDesFoot[1]; |
| suribe | 29:a88dd750fdbd | 285 | float l_OE = sqrt( (pow(xFootd,2) + pow(yFootd,2)) ); |
| saloutos | 17:1bb5aa45826e | 286 | 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 | 287 | float th2_des = -(3.14159f - alpha); |
| suribe | 29:a88dd750fdbd | 288 | float th1_des = -((3.14159f/2.0f) + atan2(yFootd,xFootd) - abs(asin( (l_AC/l_OE)*sin(alpha) ))); |
| saloutos | 17:1bb5aa45826e | 289 | |
| saloutos | 17:1bb5aa45826e | 290 | float dd = (Jx_th1*Jy_th2 - Jx_th2*Jy_th1); |
| saloutos | 17:1bb5aa45826e | 291 | float dth1_des = (1.0f/dd) * ( Jy_th2*vDesFoot[0] - Jx_th2*vDesFoot[1] ); |
| saloutos | 17:1bb5aa45826e | 292 | float dth2_des = (1.0f/dd) * ( -Jy_th1*vDesFoot[0] + Jx_th1*vDesFoot[1] ); |
| saloutos | 17:1bb5aa45826e | 293 | |
| saloutos | 16:f9ea2b2d410f | 294 | // Calculate error variables |
| saloutos | 19:562c08086d71 | 295 | float e_x = 0; |
| saloutos | 19:562c08086d71 | 296 | float e_y = 0; |
| saloutos | 19:562c08086d71 | 297 | float de_x = 0; |
| saloutos | 19:562c08086d71 | 298 | float de_y = 0; |
| saloutos | 17:1bb5aa45826e | 299 | |
| saloutos | 16:f9ea2b2d410f | 300 | // Calculate virtual force on foot |
| suribe | 29:a88dd750fdbd | 301 | float xdelta = -xFootd - xFoot; |
| suribe | 29:a88dd750fdbd | 302 | float ydelta = yFootd - yFoot; |
| suribe | 29:a88dd750fdbd | 303 | float dydelta = vDesFoot[1] - dyFoot; |
| suribe | 29:a88dd750fdbd | 304 | float dxdelta = vDesFoot[0] - dxFoot; |
| suribe | 29:a88dd750fdbd | 305 | float fx = K_xx*xdelta+K_xy*ydelta+D_xx*dxdelta+D_xy*dydelta; |
| suribe | 29:a88dd750fdbd | 306 | float fy = K_yy*ydelta+K_xy*xdelta+D_yy*dydelta+D_xy*dxdelta; |
| suribe | 29:a88dd750fdbd | 307 | |
| suribe | 29:a88dd750fdbd | 308 | float t1 = Jx_th1*fx + Jy_th1*fy; |
| suribe | 29:a88dd750fdbd | 309 | float t2 = Jx_th2*fx + Jy_th2*fy; |
| saloutos | 26:5822d4d8dca7 | 310 | |
| saloutos | 26:5822d4d8dca7 | 311 | // Calculate mass matrix elements |
| suribe | 29:a88dd750fdbd | 312 | float M11 = I1 + I2 + I3 + I4 + Ir + Ir*N*N + l_AC*l_AC*m4 + l_A_m3*l_A_m3*m3 + l_B_m2*l_B_m2*m2 + l_C_m4*l_C_m4*m4 + l_OA*l_OA*m3 + l_OB*l_OB*m2 + l_OA*l_OA*m4 + l_O_m1*l_O_m1*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); |
| suribe | 29:a88dd750fdbd | 313 | float M12 = I2 + I3 + l_AC*l_AC*m4 + l_A_m3*l_A_m3*m3 + l_B_m2*l_B_m2*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); |
| suribe | 29:a88dd750fdbd | 314 | float M22 = Ir*N*N + m4*l_AC*l_AC + m3*l_A_m3*l_A_m3 + m2*l_B_m2*l_B_m2 + I2 + I3; |
| suribe | 29:a88dd750fdbd | 315 | |
| saloutos | 26:5822d4d8dca7 | 316 | // Populate mass matrix |
| saloutos | 26:5822d4d8dca7 | 317 | MassMatrix.Clear(); |
| saloutos | 26:5822d4d8dca7 | 318 | MassMatrix << M11 << M12 |
| saloutos | 26:5822d4d8dca7 | 319 | << M12 << M22; |
| saloutos | 26:5822d4d8dca7 | 320 | |
| saloutos | 26:5822d4d8dca7 | 321 | // Populate Jacobian matrix |
| saloutos | 26:5822d4d8dca7 | 322 | Jacobian.Clear(); |
| saloutos | 26:5822d4d8dca7 | 323 | Jacobian << Jx_th1 << Jx_th2 |
| saloutos | 26:5822d4d8dca7 | 324 | << Jy_th1 << Jy_th2; |
| saloutos | 26:5822d4d8dca7 | 325 | |
| saloutos | 26:5822d4d8dca7 | 326 | // Calculate Lambda matrix |
| saloutos | 26:5822d4d8dca7 | 327 | JacobianT = MatrixMath::Transpose(Jacobian); |
| saloutos | 26:5822d4d8dca7 | 328 | InverseMassMatrix = MatrixMath::Inv(MassMatrix); |
| saloutos | 26:5822d4d8dca7 | 329 | temp_product = Jacobian*InverseMassMatrix*JacobianT; |
| saloutos | 26:5822d4d8dca7 | 330 | Lambda = MatrixMath::Inv(temp_product); |
| saloutos | 26:5822d4d8dca7 | 331 | |
| saloutos | 26:5822d4d8dca7 | 332 | // Pull elements of Lambda matrix |
| saloutos | 26:5822d4d8dca7 | 333 | float L11 = Lambda.getNumber(1,1); |
| saloutos | 26:5822d4d8dca7 | 334 | float L12 = Lambda.getNumber(1,2); |
| saloutos | 26:5822d4d8dca7 | 335 | float L21 = Lambda.getNumber(2,1); |
| suribe | 29:a88dd750fdbd | 336 | float L22 = Lambda.getNumber(2,2); |
| suribe | 29:a88dd750fdbd | 337 | |
| suribe | 32:c60a5d33cd79 | 338 | // Calculate desired motor torque |
| suribe | 29:a88dd750fdbd | 339 | float t1_op = (Jx_th1*L11+Jy_th1*L21)*fx + (Jx_th1*L12+Jy_th1*L22)*fy; |
| suribe | 29:a88dd750fdbd | 340 | float t2_op = (Jx_th2*L11+Jy_th2*L21)*fx + (Jx_th2*L12+Jy_th2*L22)*fy; |
| saloutos | 18:21c8d94eddee | 341 | |
| saloutos | 19:562c08086d71 | 342 | // Set desired currents |
| suribe | 29:a88dd750fdbd | 343 | current_des1 = t1_op/k_t; |
| suribe | 29:a88dd750fdbd | 344 | current_des2 = t2_op/k_t; |
| saloutos | 26:5822d4d8dca7 | 345 | |
| saloutos | 19:562c08086d71 | 346 | // Form output to send to MATLAB |
| saloutos | 16:f9ea2b2d410f | 347 | float output_data[NUM_OUTPUTS]; |
| saloutos | 16:f9ea2b2d410f | 348 | // current time |
| pwensing | 0:43448bf056e8 | 349 | output_data[0] = t.read(); |
| saloutos | 16:f9ea2b2d410f | 350 | // motor 1 state |
| saloutos | 16:f9ea2b2d410f | 351 | output_data[1] = angle1; |
| saloutos | 16:f9ea2b2d410f | 352 | output_data[2] = velocity1; |
| saloutos | 16:f9ea2b2d410f | 353 | output_data[3] = current1; |
| saloutos | 16:f9ea2b2d410f | 354 | output_data[4] = current_des1; |
| saloutos | 16:f9ea2b2d410f | 355 | output_data[5] = duty_cycle1; |
| saloutos | 16:f9ea2b2d410f | 356 | // motor 2 state |
| saloutos | 16:f9ea2b2d410f | 357 | output_data[6] = angle2; |
| saloutos | 16:f9ea2b2d410f | 358 | output_data[7] = velocity2; |
| saloutos | 16:f9ea2b2d410f | 359 | output_data[8] = current2; |
| saloutos | 16:f9ea2b2d410f | 360 | output_data[9] = current_des2; |
| saloutos | 16:f9ea2b2d410f | 361 | output_data[10]= duty_cycle2; |
| saloutos | 16:f9ea2b2d410f | 362 | // foot state |
| saloutos | 16:f9ea2b2d410f | 363 | output_data[11] = xFoot; |
| saloutos | 16:f9ea2b2d410f | 364 | output_data[12] = yFoot; |
| saloutos | 17:1bb5aa45826e | 365 | output_data[13] = dxFoot; |
| saloutos | 17:1bb5aa45826e | 366 | output_data[14] = dyFoot; |
| saloutos | 17:1bb5aa45826e | 367 | output_data[15] = rDesFoot[0]; |
| saloutos | 17:1bb5aa45826e | 368 | output_data[16] = rDesFoot[1]; |
| saloutos | 17:1bb5aa45826e | 369 | output_data[17] = vDesFoot[0]; |
| saloutos | 17:1bb5aa45826e | 370 | output_data[18] = vDesFoot[1]; |
| elijahsj | 13:3a1f4e09789b | 371 | |
| pwensing | 0:43448bf056e8 | 372 | // Send data to MATLAB |
| pwensing | 0:43448bf056e8 | 373 | server.sendData(output_data,NUM_OUTPUTS); |
| saloutos | 16:f9ea2b2d410f | 374 | |
| saloutos | 16:f9ea2b2d410f | 375 | wait_us(impedance_control_period_us); |
| elijahsj | 4:7a1b35f081bb | 376 | } |
| saloutos | 16:f9ea2b2d410f | 377 | |
| pwensing | 0:43448bf056e8 | 378 | // Cleanup after experiment |
| pwensing | 0:43448bf056e8 | 379 | server.setExperimentComplete(); |
| saloutos | 16:f9ea2b2d410f | 380 | currentLoop.detach(); |
| elijahsj | 12:84a6dcb60422 | 381 | motorShield.motorAWrite(0, 0); //turn motor A off |
| saloutos | 16:f9ea2b2d410f | 382 | motorShield.motorBWrite(0, 0); //turn motor B off |
| pwensing | 0:43448bf056e8 | 383 | } // end if |
| pwensing | 0:43448bf056e8 | 384 | } // end while |
| suribe | 32:c60a5d33cd79 | 385 | } // end main |
