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