test

Dependencies:   ExperimentServer QEI_pmw MotorShield

Committer:
mayborne_
Date:
Thu Dec 09 23:55:33 2021 +0000
Revision:
26:93506abcf763
Parent:
25:52b378e89f42
test

Who changed what in which revision?

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