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