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