Version for EMG Threshold finding

Dependencies:   HIDScope MODSERIAL QEI biquadFilter mbed

Fork of prog_BioRobotics_Group9_StampRobot by Gerhard Berman

Committer:
GerhardBerman
Date:
Thu Nov 03 10:43:06 2016 +0000
Revision:
38:e58bab07275e
Parent:
36:72f0913c5460
Child:
39:cc7754330c26
Added minimal RefPosition boundary

Who changed what in which revision?

UserRevisionLine numberNew contents of line
GerhardBerman 0:43160ef59f9f 1 #include "mbed.h"
GerhardBerman 0:43160ef59f9f 2 #include <math.h>
GerhardBerman 0:43160ef59f9f 3 #include "MODSERIAL.h"
GerhardBerman 0:43160ef59f9f 4 #include "QEI.h"
GerhardBerman 0:43160ef59f9f 5 #include "HIDScope.h"
GerhardBerman 0:43160ef59f9f 6 #include "BiQuad.h"
GerhardBerman 0:43160ef59f9f 7
GerhardBerman 17:91d20d362e72 8 /*
GerhardBerman 17:91d20d362e72 9 THINGS TO CONSIDER
GerhardBerman 17:91d20d362e72 10 - Line 234, 239: motor action of motor 1 is inverted because it is mounted
GerhardBerman 17:91d20d362e72 11 opposite to motor 2 in the tower. Check if the clockwise directions of the
GerhardBerman 17:91d20d362e72 12 motors correspond to the positive q1, q2-directions (both counterclockwise)
GerhardBerman 17:91d20d362e72 13 in the original IK-sketch.
GerhardBerman 17:91d20d362e72 14 - Line 244,257: motor values have been scaled down for safety at first test, restore
GerhardBerman 17:91d20d362e72 15 after testing to get proper action.
GerhardBerman 19:cba54636bd62 16 - Set angle and length boundaries!!
GerhardBerman 17:91d20d362e72 17 - Set robot constants (lengths etc.)
GerhardBerman 18:d2cfd07ae88a 18 - Set EMGgain and thresholds
GerhardBerman 23:3a4d5e19c20d 19 - Add tower height to ReferencePosition_y and Position_y AND inverse kinematics calculation!
GerhardBerman 22:c679f753a8bd 20 - Add (lower) boundaries to TotalErrors
GerhardBerman 22:c679f753a8bd 21 - MotorGain could change due to arm weight!!
GerhardBerman 22:c679f753a8bd 22 - Arms should be placed manually into reference position.
GerhardBerman 17:91d20d362e72 23 */
GerhardBerman 17:91d20d362e72 24
GerhardBerman 0:43160ef59f9f 25 //set pins
GerhardBerman 0:43160ef59f9f 26 DigitalIn encoder1A (D13); //Channel A van Encoder 1
GerhardBerman 0:43160ef59f9f 27 DigitalIn encoder1B (D12); //Channel B van Encoder 1
GerhardBerman 14:725a608b6709 28 DigitalIn encoder2A (D11); //Channel A van Encoder 2, kan niet op D15
GerhardBerman 14:725a608b6709 29 DigitalIn encoder2B (D10); //Channel B van Encoder 2, kan niet op D14
GerhardBerman 14:725a608b6709 30 //DigitalOut led1 (D11);
GerhardBerman 14:725a608b6709 31 //DigitalOut led2 (D10);
GerhardBerman 19:cba54636bd62 32 //AnalogIn potMeter1(A2);
GerhardBerman 19:cba54636bd62 33 //AnalogIn potMeter2(A1);
GerhardBerman 0:43160ef59f9f 34 DigitalOut motor1DirectionPin(D7);
GerhardBerman 0:43160ef59f9f 35 PwmOut motor1MagnitudePin(D6);
GerhardBerman 7:2f74dfd1d411 36 DigitalOut motor2DirectionPin(D4);
GerhardBerman 7:2f74dfd1d411 37 PwmOut motor2MagnitudePin(D5);
GerhardBerman 9:e4c34f5665a0 38 DigitalIn button1(D3);
GerhardBerman 7:2f74dfd1d411 39 DigitalIn button2(D9);
GerhardBerman 0:43160ef59f9f 40
GerhardBerman 33:b09608fa69e9 41 DigitalOut ledgrn(LED_GREEN);
GerhardBerman 33:b09608fa69e9 42 DigitalOut ledred(LED_RED);
GerhardBerman 33:b09608fa69e9 43 DigitalOut ledblue(LED_BLUE);
GerhardBerman 33:b09608fa69e9 44
GerhardBerman 7:2f74dfd1d411 45 //library settings
GerhardBerman 0:43160ef59f9f 46 Serial pc(USBTX,USBRX);
GerhardBerman 3:8caef4872b0c 47 Ticker MeasureTicker, BiQuadTicker; //, TimeTracker; // sampleT;
GerhardBerman 33:b09608fa69e9 48 //HIDScope scope(6);
GerhardBerman 0:43160ef59f9f 49
GerhardBerman 26:bb7e14f59ddd 50 //initial values
GerhardBerman 7:2f74dfd1d411 51 float dx;
GerhardBerman 7:2f74dfd1d411 52 float dy;
GerhardBerman 23:3a4d5e19c20d 53 double DerivativeCounts;
GerhardBerman 19:cba54636bd62 54 //float referenceVelocity = 0;
GerhardBerman 19:cba54636bd62 55 //float bqcDerivativeCounts = 0;
GerhardBerman 3:8caef4872b0c 56 const float PI = 3.141592653589793;
GerhardBerman 3:8caef4872b0c 57 const int cw = 0; //values for cw and ccw are inverted!! cw=0 and ccw=1
GerhardBerman 3:8caef4872b0c 58 const int ccw = 1;
GerhardBerman 0:43160ef59f9f 59
GerhardBerman 26:bb7e14f59ddd 60 //set lengths (VALUES HAVE TO BE CHANGED)
GerhardBerman 36:72f0913c5460 61 //float x0 = 1.0;
GerhardBerman 36:72f0913c5460 62 float L0 = 0.232;
GerhardBerman 36:72f0913c5460 63 float L1 = 0.45;
GerhardBerman 36:72f0913c5460 64 float L2 = 0.35;
GerhardBerman 36:72f0913c5460 65 float TowerHeight = 0.232; //height of motor axes above table surface!
GerhardBerman 36:72f0913c5460 66 float StampHeight = 0.06; // height of end effector
GerhardBerman 34:96bcbddc7d2d 67 float y_stampup = 0.1; //height stamp while not stamping: 10cm above table surface
GerhardBerman 34:96bcbddc7d2d 68 float y_stampdown = 0.0; //height stamp while stamping: at table surface
GerhardBerman 34:96bcbddc7d2d 69
GerhardBerman 26:bb7e14f59ddd 70
GerhardBerman 19:cba54636bd62 71 //set initial conditions
GerhardBerman 19:cba54636bd62 72 float biceps_l = 0;
GerhardBerman 19:cba54636bd62 73 float biceps_r = 0;
GerhardBerman 19:cba54636bd62 74 float ReferencePosition_x = L2;
GerhardBerman 28:6d8c6fe79394 75 float ReferencePosition_y = L1 + TowerHeight - StampHeight;
GerhardBerman 19:cba54636bd62 76 float ReferencePosition_xnew = 0;
GerhardBerman 19:cba54636bd62 77 float ReferencePosition_ynew = 0;
GerhardBerman 19:cba54636bd62 78 float Position_x = 0.0;
GerhardBerman 19:cba54636bd62 79 float Position_y = 0.0;
GerhardBerman 19:cba54636bd62 80 float q1 = 0;
GerhardBerman 19:cba54636bd62 81 float q2 = 0;
GerhardBerman 19:cba54636bd62 82 float q1_ref = 0;
GerhardBerman 19:cba54636bd62 83 float q2_ref = 0;
GerhardBerman 19:cba54636bd62 84 float q1start = 0;
GerhardBerman 19:cba54636bd62 85 float q2start = PI/2;
GerhardBerman 19:cba54636bd62 86
GerhardBerman 19:cba54636bd62 87 float q1_error_prev = 0;
GerhardBerman 19:cba54636bd62 88 float q2_error_prev = 0;
GerhardBerman 25:596255732b65 89 float DerTotalError1 = 0;
GerhardBerman 25:596255732b65 90 float DerTotalError2 = 0;
GerhardBerman 19:cba54636bd62 91 float q1IntError = 0;
GerhardBerman 19:cba54636bd62 92 float q2IntError = 0;
GerhardBerman 29:caf3dd699617 93 float TotalError1_prev = 0;
GerhardBerman 29:caf3dd699617 94 float TotalError2_prev = 0;
GerhardBerman 19:cba54636bd62 95
GerhardBerman 19:cba54636bd62 96 float motorValue1 = 0.0;
GerhardBerman 19:cba54636bd62 97 float motorValue2 = 0.0;
GerhardBerman 19:cba54636bd62 98 int counts1 = 0;
GerhardBerman 19:cba54636bd62 99 int counts2 = 0;
GerhardBerman 19:cba54636bd62 100 int counts1Prev = 0;
GerhardBerman 19:cba54636bd62 101 int counts2Prev = 0;
GerhardBerman 26:bb7e14f59ddd 102
GerhardBerman 26:bb7e14f59ddd 103
GerhardBerman 26:bb7e14f59ddd 104 //set constant or variable values (VALUES HAVE TO BE EDITED)
GerhardBerman 26:bb7e14f59ddd 105 float EMGgain = 1.0;
GerhardBerman 26:bb7e14f59ddd 106 float dy_stampdown = 2.0; //0.05; //5 cm movement downward to stamp
GerhardBerman 26:bb7e14f59ddd 107 float MotorGain = 8.4; // rad/s for PWM, is max motor speed (motor value of 1)
GerhardBerman 38:e58bab07275e 108 float MotorMaxSpeed = 0.5; //define a maximum PWM speed for the motor
GerhardBerman 34:96bcbddc7d2d 109 float t_sample = 0.1; //seconds
GerhardBerman 34:96bcbddc7d2d 110 const float maxStampDistance = 2.0;
GerhardBerman 26:bb7e14f59ddd 111
GerhardBerman 26:bb7e14f59ddd 112 float q1_refOutNew = 0;
GerhardBerman 38:e58bab07275e 113 float q1_refOutMin = 0; //Min angle in radians
GerhardBerman 38:e58bab07275e 114 float q1_refOutMax = 1.47; //Max angle in radians
GerhardBerman 26:bb7e14f59ddd 115 float q2_refOutNew = 0;
GerhardBerman 38:e58bab07275e 116 float q2_refOutMin = 0.81; //Min angle in radians
GerhardBerman 38:e58bab07275e 117 float q2_refOutMax = 2.17; //Max angle in radians
GerhardBerman 26:bb7e14f59ddd 118 float TotalError1= 0;
GerhardBerman 26:bb7e14f59ddd 119 float TotalError2= 0;
GerhardBerman 26:bb7e14f59ddd 120 float TotalErrorMin= 0;
GerhardBerman 19:cba54636bd62 121
GerhardBerman 0:43160ef59f9f 122 //set BiQuad
GerhardBerman 0:43160ef59f9f 123 BiQuadChain bqc;
GerhardBerman 0:43160ef59f9f 124 BiQuad bq1(0.0186, 0.0743, 0.1114, 0.0743, 0.0186); //get numbers from butter filter MATLAB
GerhardBerman 0:43160ef59f9f 125 BiQuad bq2(1.0000, -1.5704, 1.2756, -0.4844, 0.0762);
GerhardBerman 0:43160ef59f9f 126
GerhardBerman 0:43160ef59f9f 127 //set go-Ticker settings
GerhardBerman 3:8caef4872b0c 128 volatile bool MeasureTicker_go=false, BiQuadTicker_go=false, FeedbackTicker_go=false, TimeTracker_go=false; // sampleT_go=false;
GerhardBerman 3:8caef4872b0c 129 void MeasureTicker_act(){MeasureTicker_go=true;}; // Activates go-flags
GerhardBerman 3:8caef4872b0c 130 void BiQuadTicker_act(){BiQuadTicker_go=true;};
GerhardBerman 3:8caef4872b0c 131 void FeedbackTicker_act(){FeedbackTicker_go=true;};
GerhardBerman 3:8caef4872b0c 132 void TimeTracker_act(){TimeTracker_go=true;};
GerhardBerman 3:8caef4872b0c 133 //void sampleT_act(){sampleT_go=true;};
GerhardBerman 3:8caef4872b0c 134
GerhardBerman 3:8caef4872b0c 135 //define encoder counts and degrees
GerhardBerman 7:2f74dfd1d411 136 QEI Encoder1(D12, D13, NC, 32); // turns on encoder
GerhardBerman 15:9061cf7db23e 137 QEI Encoder2(D10, D11, NC, 32); // turns on encoder
GerhardBerman 14:725a608b6709 138
GerhardBerman 4:19e376d31380 139 const int counts_per_revolution = 4200; //counts per motor axis revolution
GerhardBerman 4:19e376d31380 140 const int inverse_gear_ratio = 131;
GerhardBerman 4:19e376d31380 141 const float resolution = counts_per_revolution/(2*PI/inverse_gear_ratio); //87567.0496892 counts per radian, encoder axis
GerhardBerman 3:8caef4872b0c 142
GerhardBerman 19:cba54636bd62 143 void GetReferenceKinematics1(float &q1Out, float &q2Out, float &q1_refOut, float &q2_refOut){
GerhardBerman 7:2f74dfd1d411 144
GerhardBerman 19:cba54636bd62 145 //get joint positions q feedback from encoder
GerhardBerman 19:cba54636bd62 146 float Encoder1Position = counts1/resolution; //angular position in radians, encoder axis
GerhardBerman 9:e4c34f5665a0 147 float Encoder2Position = counts2/resolution;
GerhardBerman 19:cba54636bd62 148
GerhardBerman 19:cba54636bd62 149 q1Out = q1start + Encoder1Position*inverse_gear_ratio; //angular position in radians, motor axis
GerhardBerman 19:cba54636bd62 150 q2Out = q2start + Encoder2Position*inverse_gear_ratio;
GerhardBerman 7:2f74dfd1d411 151
GerhardBerman 19:cba54636bd62 152 /*
GerhardBerman 19:cba54636bd62 153 //get end effector position feedback with Brockett
GerhardBerman 18:d2cfd07ae88a 154 float Position_x = ((L2 + x0)*(cos(q1)*cos(q2) - sin(q1)*sin(q2)) - L0*sin(q1) + (cos(q1)*sin(q2) + cos(q2)*sin(q1))*(L0 + L1) - cos(q1)*(L1*sin(q1) + L1*cos(q1)*sin(q2) - L1*cos(q2)*sin(q1)) - sin(q1)*(L1*cos(q1)*cos(q2) - L1*cos(q1) + L1*sin(q1)*sin(q2))); //calculate end effector x-position from motor angles with Brockett, rx
GerhardBerman 18:d2cfd07ae88a 155 float Position_y = (L0 - (L2 + x0)*(cos(q1)*sin(q2) + cos(q2)*sin(q1)) - L0*cos(q1) - cos(q1)*(L1*cos(q1)*cos(q2) - L1*cos(q1) + L1*sin(q1)*sin(q2)) + (cos(q1)*cos(q2) - sin(q1)*sin(q2))*(L0 + L1) + sin(q1)*(L1*sin(q1) + L1*cos(q1)*sin(q2) - L1*cos(q2)*sin(q1))); //calculate end effector y-position from motor angles with Brockett, ry
GerhardBerman 19:cba54636bd62 156 */
GerhardBerman 19:cba54636bd62 157 //get end effector position feedback with trigonometry
GerhardBerman 19:cba54636bd62 158 Position_x = (L1*sin(q1) + L2*sin(q1+q2));
GerhardBerman 28:6d8c6fe79394 159 Position_y = (L1*cos(q1) + L2*cos(q1+q2)) + TowerHeight - StampHeight;
GerhardBerman 19:cba54636bd62 160 //float PositionVector = sqrt(pow(Position_x,2)+pow(Position_y,2));
GerhardBerman 29:caf3dd699617 161
GerhardBerman 33:b09608fa69e9 162 /*
GerhardBerman 29:caf3dd699617 163 if (Position_y < (0.5*TowerHeight)){
GerhardBerman 29:caf3dd699617 164 wait(1.0);
GerhardBerman 29:caf3dd699617 165 ReferencePosition_ynew = L1 + TowerHeight - StampHeight; //Reset vertical position after stamping
GerhardBerman 29:caf3dd699617 166 }
GerhardBerman 29:caf3dd699617 167 else{
GerhardBerman 33:b09608fa69e9 168 */
GerhardBerman 7:2f74dfd1d411 169 //get velocity vector v = (Pe*- Pe) = [0; dx; dy] from EMG
GerhardBerman 19:cba54636bd62 170 biceps_l = !button1.read() * EMGgain; //emg0.read(); //velocity or reference position change, EMG with a gain
GerhardBerman 19:cba54636bd62 171 biceps_r = !button2.read() * EMGgain; //emg1.read();
GerhardBerman 18:d2cfd07ae88a 172 if (biceps_l > 0 && biceps_r > 0){
GerhardBerman 8:935abf8ecc27 173 //both arms activated: stamp moves down
GerhardBerman 15:9061cf7db23e 174 //led1 = 1;
GerhardBerman 15:9061cf7db23e 175 //led2 = 1;
GerhardBerman 19:cba54636bd62 176 ReferencePosition_xnew = ReferencePosition_x;
GerhardBerman 34:96bcbddc7d2d 177 ReferencePosition_ynew = y_stampdown; //ReferencePosition_y - dy_stampdown; //into stamping vertical position ~the stamp down action
GerhardBerman 18:d2cfd07ae88a 178
GerhardBerman 18:d2cfd07ae88a 179 }
GerhardBerman 18:d2cfd07ae88a 180 else if (biceps_l > 0 && biceps_r <= 0){
GerhardBerman 18:d2cfd07ae88a 181 //arm 1 activated, move left
GerhardBerman 18:d2cfd07ae88a 182 //led1 = 1;
GerhardBerman 18:d2cfd07ae88a 183 //led2 = 0;
GerhardBerman 19:cba54636bd62 184 ReferencePosition_xnew = ReferencePosition_x - 0.2; //biceps_l;
GerhardBerman 34:96bcbddc7d2d 185 ReferencePosition_ynew = y_stampup; //ReferencePosition_y;
GerhardBerman 12:05e5964b69a4 186 /*
GerhardBerman 18:d2cfd07ae88a 187 PositionError_x = ReferencePosition_x - Position_x; //Position error in dx,dy
GerhardBerman 18:d2cfd07ae88a 188 PositionError_y = ReferencePosition_y - Position_y; //Position error in dx,dy
GerhardBerman 18:d2cfd07ae88a 189
GerhardBerman 18:d2cfd07ae88a 190 dx = PositionError_x;
GerhardBerman 18:d2cfd07ae88a 191 dy = PositionError_y;
GerhardBerman 12:05e5964b69a4 192 q1_dotOut = dy*(((x0 + L1*cos(q1))*(L0*L0 + L1*sin(q1)*L0 + x0*x0 + L1*cos(q1)*x0 + 1))/(pow(L1*cos(q1),2) + pow(L1*sin(q1),2) + pow(L1*x0*sin(q1),2) + pow(L0*L1*cos(q1),2) - 2*L0*L1*L1*x0*cos(q1)*sin(q1)) - (x0*(pow(L1*cos(q1),2) + pow(L1*sin(q1),2) + L0*L0 + x0*x0 + 2*L0*L1*sin(q1) + 2*L1*x0*cos(q1) + 1))/(pow(L1*cos(q1),2) + pow(L1*sin(q1),2) + pow(L1*x0*sin(q1),2) + pow(L0*L1*cos(q1),2) - 2*L0*L1*L1*x0*cos(q1)*sin(q1))) - dx*(((L0 + L1*sin(q1))*(L0*L0 + L1*sin(q1)*L0 + x0*x0 + L1*cos(q1)*x0 + 1))/(pow(L1*cos(q1),2) + pow(L1*sin(q1),2) + pow(L1*x0*sin(q1),2) + pow(L0*L1*cos(q1),2) - 2*L0*L1*L1*x0*cos(q1)*sin(q1)) - (L0*(pow(L1*cos(q1),2) + pow(L1*sin(q1),2) + L0*L0 + x0*x0 + 2*L0*L1*sin(q1) + 2*L1*x0*cos(q1) + 1))/(pow(L1*cos(q1),2) + pow(L1*sin(q1),2) + pow(L1*x0*sin(q1),2) + pow(L0*L1*cos(q1),2) - 2*L0*L1*L1*x0*cos(q1)*sin(q1)));
GerhardBerman 12:05e5964b69a4 193 q2_dotOut = dy*((x0*(L0*L0 + L1*sin(q1)*L0 + x0*x0 + L1*cos(q1)*x0 + 1))/(L1*L1*pow(cos(q1),2) + pow(L1*sin(q1),2) + pow(L1*x0*sin(q1),2) + pow(L0*L1*cos(q1),2) - 2*L0*pow(L1,2)*x0*cos(q1)*sin(q1)) - ((x0 + L1*cos(q1))*(pow(L0,2) + pow(x0,2) + 1))/(pow(L1*cos(q1),2)) + pow(L1*sin(q1),2) + pow(L1*x0*sin(q1),2) + pow(L0*L1*cos(q1),2) - 2*L0*pow(L1,2)*x0*cos(q1)*sin(q1)) - dx*((L0*(L0*L0+L1*sin(q1)*L0+x0*x0+L1*cos(q1)*x0+1))/(pow(L1*cos(q1),2)+pow(L1*sin(q1),2)+pow(L1*x0*sin(q1),2)+pow(L0*L1*cos(q1),2)-2*L0*L1*L1*x0*cos(q1)*sin(q1))-((L0 + L1*sin(q1))*(L0*L0 + x0*x0 + 1))/(pow(L1*cos(q1),2)+pow(L1*sin(q1),2)+pow(L1*x0*sin(q1),2)+pow(L0*L1*cos(q1),2)-2*L0*L1*L1*x0*cos(q1)*sin(q1)));
GerhardBerman 12:05e5964b69a4 194 */
GerhardBerman 8:935abf8ecc27 195 }
GerhardBerman 18:d2cfd07ae88a 196 else if (biceps_l <= 0 && biceps_r > 0){
GerhardBerman 18:d2cfd07ae88a 197 //arm 1 activated, move right
GerhardBerman 18:d2cfd07ae88a 198 //led1 = 0;
GerhardBerman 18:d2cfd07ae88a 199 //led2 = 1;
GerhardBerman 19:cba54636bd62 200 ReferencePosition_xnew = ReferencePosition_x + 0.2; //biceps_r;
GerhardBerman 34:96bcbddc7d2d 201 ReferencePosition_ynew = y_stampup; //ReferencePosition_y;
GerhardBerman 18:d2cfd07ae88a 202 /*PositionError_x = ReferencePosition_x - Position_x; //Position error in dx,dy
GerhardBerman 18:d2cfd07ae88a 203 PositionError_y = ReferencePosition_y - Position_y; //Position error in dx,dy
GerhardBerman 18:d2cfd07ae88a 204
GerhardBerman 18:d2cfd07ae88a 205 dx = PositionError_x;
GerhardBerman 18:d2cfd07ae88a 206 dy = PositionError_y;
GerhardBerman 12:05e5964b69a4 207 q1_dotOut = dy*(((x0 + L1*cos(q1))*(L0*L0 + L1*sin(q1)*L0 + x0*x0 + L1*cos(q1)*x0 + 1))/(pow(L1*cos(q1),2) + pow(L1*sin(q1),2) + pow(L1*x0*sin(q1),2) + pow(L0*L1*cos(q1),2) - 2*L0*L1*L1*x0*cos(q1)*sin(q1)) - (x0*(pow(L1*cos(q1),2) + pow(L1*sin(q1),2) + L0*L0 + x0*x0 + 2*L0*L1*sin(q1) + 2*L1*x0*cos(q1) + 1))/(pow(L1*cos(q1),2) + pow(L1*sin(q1),2) + pow(L1*x0*sin(q1),2) + pow(L0*L1*cos(q1),2) - 2*L0*L1*L1*x0*cos(q1)*sin(q1))) - dx*(((L0 + L1*sin(q1))*(L0*L0 + L1*sin(q1)*L0 + x0*x0 + L1*cos(q1)*x0 + 1))/(pow(L1*cos(q1),2) + pow(L1*sin(q1),2) + pow(L1*x0*sin(q1),2) + pow(L0*L1*cos(q1),2) - 2*L0*L1*L1*x0*cos(q1)*sin(q1)) - (L0*(pow(L1*cos(q1),2) + pow(L1*sin(q1),2) + L0*L0 + x0*x0 + 2*L0*L1*sin(q1) + 2*L1*x0*cos(q1) + 1))/(pow(L1*cos(q1),2) + pow(L1*sin(q1),2) + pow(L1*x0*sin(q1),2) + pow(L0*L1*cos(q1),2) - 2*L0*L1*L1*x0*cos(q1)*sin(q1)));
GerhardBerman 12:05e5964b69a4 208 q2_dotOut = dy*((x0*(L0*L0 + L1*sin(q1)*L0 + x0*x0 + L1*cos(q1)*x0 + 1))/(L1*L1*pow(cos(q1),2) + pow(L1*sin(q1),2) + pow(L1*x0*sin(q1),2) + pow(L0*L1*cos(q1),2) - 2*L0*pow(L1,2)*x0*cos(q1)*sin(q1)) - ((x0 + L1*cos(q1))*(pow(L0,2) + pow(x0,2) + 1))/(pow(L1*cos(q1),2)) + pow(L1*sin(q1),2) + pow(L1*x0*sin(q1),2) + pow(L0*L1*cos(q1),2) - 2*L0*pow(L1,2)*x0*cos(q1)*sin(q1)) - dx*((L0*(L0*L0+L1*sin(q1)*L0+x0*x0+L1*cos(q1)*x0+1))/(pow(L1*cos(q1),2)+pow(L1*sin(q1),2)+pow(L1*x0*sin(q1),2)+pow(L0*L1*cos(q1),2)-2*L0*L1*L1*x0*cos(q1)*sin(q1))-((L0 + L1*sin(q1))*(L0*L0 + x0*x0 + 1))/(pow(L1*cos(q1),2)+pow(L1*sin(q1),2)+pow(L1*x0*sin(q1),2)+pow(L0*L1*cos(q1),2)-2*L0*L1*L1*x0*cos(q1)*sin(q1)));
GerhardBerman 18:d2cfd07ae88a 209 */
GerhardBerman 8:935abf8ecc27 210 }
GerhardBerman 8:935abf8ecc27 211 else{
GerhardBerman 15:9061cf7db23e 212 //led1 = 0;
GerhardBerman 15:9061cf7db23e 213 //led2 = 0;
GerhardBerman 19:cba54636bd62 214 ReferencePosition_xnew = ReferencePosition_x;
GerhardBerman 36:72f0913c5460 215 ReferencePosition_ynew = y_stampup; //ReferencePosition_y; //
GerhardBerman 19:cba54636bd62 216 }
GerhardBerman 33:b09608fa69e9 217 // }
GerhardBerman 19:cba54636bd62 218
GerhardBerman 28:6d8c6fe79394 219 float PointPositionArm2_x = ReferencePosition_x;
GerhardBerman 28:6d8c6fe79394 220 float PointPositionArm2_y = ReferencePosition_y - TowerHeight + StampHeight;
GerhardBerman 28:6d8c6fe79394 221 float PointVectorArm2 = sqrt(pow(PointPositionArm2_x,2)+pow(PointPositionArm2_y,2));
GerhardBerman 19:cba54636bd62 222
GerhardBerman 19:cba54636bd62 223 //check position boundaries
GerhardBerman 28:6d8c6fe79394 224 if (PointVectorArm2 > maxStampDistance){
GerhardBerman 34:96bcbddc7d2d 225 ReferencePosition_x = ReferencePosition_x - 0.1;
GerhardBerman 34:96bcbddc7d2d 226 ReferencePosition_y = y_stampup;
GerhardBerman 34:96bcbddc7d2d 227 pc.printf("Target too far! \r\n");
GerhardBerman 19:cba54636bd62 228 }
GerhardBerman 38:e58bab07275e 229 else if {PointVectorArm2 < minStampDistance){
GerhardBerman 38:e58bab07275e 230 ReferencePosition_x = ReferencePosition_x + 0.1;
GerhardBerman 38:e58bab07275e 231 ReferencePosition_y = y_stampup;
GerhardBerman 38:e58bab07275e 232 pc.printf("Target too far! \r\n");
GerhardBerman 19:cba54636bd62 233 else {
GerhardBerman 19:cba54636bd62 234 ReferencePosition_x = ReferencePosition_xnew;
GerhardBerman 19:cba54636bd62 235 ReferencePosition_y = ReferencePosition_ynew;
11i 20:201175fa8a2a 236 }
GerhardBerman 19:cba54636bd62 237
GerhardBerman 19:cba54636bd62 238 //calculate reference joint angles for the new reference position
GerhardBerman 28:6d8c6fe79394 239 float alpha = atan(PointPositionArm2_y/PointPositionArm2_x);
GerhardBerman 28:6d8c6fe79394 240 float beta = acos((L2*L2-L1*L1-pow(PointVectorArm2,2))/(-2*L1*PointVectorArm2));
GerhardBerman 19:cba54636bd62 241 q1_refOutNew = PI/2 - (alpha+beta);
GerhardBerman 28:6d8c6fe79394 242 q2_refOutNew = PI - asin(PointVectorArm2*sin(beta)/L2);
GerhardBerman 19:cba54636bd62 243
GerhardBerman 19:cba54636bd62 244 //check angle boundaries
GerhardBerman 27:456e8a47f815 245 if (q1_refOutNew > q1_refOutMin && q1_refOutNew < q1_refOutMax){
GerhardBerman 19:cba54636bd62 246 q1_refOut = q1_refOutNew;
GerhardBerman 19:cba54636bd62 247 }
GerhardBerman 19:cba54636bd62 248 else {
GerhardBerman 19:cba54636bd62 249 q1_refOut = q1_refOut;
GerhardBerman 19:cba54636bd62 250 }
GerhardBerman 27:456e8a47f815 251 if (q2_refOutNew > q2_refOutMin && q2_refOutNew < q2_refOutMax){
GerhardBerman 19:cba54636bd62 252 q2_refOut = q2_refOutNew;
GerhardBerman 19:cba54636bd62 253 }
GerhardBerman 19:cba54636bd62 254 else {
GerhardBerman 19:cba54636bd62 255 q2_refOut = q2_refOut;
GerhardBerman 19:cba54636bd62 256 }
GerhardBerman 18:d2cfd07ae88a 257
GerhardBerman 7:2f74dfd1d411 258 //update joint angles
GerhardBerman 18:d2cfd07ae88a 259 //q1Out = q1Out + q1_dotOut; //in radians
GerhardBerman 18:d2cfd07ae88a 260 //q2Out = q2Out + q2_dotOut;
GerhardBerman 12:05e5964b69a4 261
GerhardBerman 34:96bcbddc7d2d 262 pc.baud(115200);
GerhardBerman 36:72f0913c5460 263 pc.printf("posX: %f ",Position_x);
GerhardBerman 36:72f0913c5460 264 pc.printf("posY: %f ",Position_y);
GerhardBerman 34:96bcbddc7d2d 265 pc.printf("refX: %f ",ReferencePosition_xnew);
GerhardBerman 34:96bcbddc7d2d 266 pc.printf("refY: %f ",ReferencePosition_ynew);
GerhardBerman 34:96bcbddc7d2d 267 pc.printf("q1: %f ", q1Out);
GerhardBerman 34:96bcbddc7d2d 268 pc.printf("q1ref: %f ", q1_refOut);
GerhardBerman 34:96bcbddc7d2d 269 pc.printf("q2: %f ", q2Out);
GerhardBerman 34:96bcbddc7d2d 270 pc.printf("q2ref: %f ", q2_refOut);
GerhardBerman 19:cba54636bd62 271
GerhardBerman 18:d2cfd07ae88a 272 /*
GerhardBerman 12:05e5964b69a4 273 pc.printf("dx: %f \r\n", dx);
GerhardBerman 12:05e5964b69a4 274 pc.printf("dy: %f \r\n", dy);
GerhardBerman 12:05e5964b69a4 275 pc.printf("q1: %f \r\n", q1Out);
GerhardBerman 12:05e5964b69a4 276 pc.printf("q1_dot: %f \r\n", q1_dotOut);
GerhardBerman 12:05e5964b69a4 277 pc.printf("q2: %f \r\n", q2Out);
GerhardBerman 12:05e5964b69a4 278 pc.printf("q2_dot: %f \r\n", q2_dotOut);
GerhardBerman 12:05e5964b69a4 279
GerhardBerman 14:725a608b6709 280 pc.printf("Counts1: %f \r\n", counts1);
GerhardBerman 14:725a608b6709 281 pc.printf("Encoder1: %f \r\n", Encoder1Position);
GerhardBerman 18:d2cfd07ae88a 282 pc.printf("Motor1: %f \r\n", q1Out);
GerhardBerman 14:725a608b6709 283 pc.printf("Counts2: %f \r\n", counts2);
GerhardBerman 14:725a608b6709 284 pc.printf("Encoder2: %f \r\n", Encoder2Position);
GerhardBerman 18:d2cfd07ae88a 285 pc.printf("Motor2: %f \r\n", q2Out);
GerhardBerman 18:d2cfd07ae88a 286 */
GerhardBerman 29:caf3dd699617 287
GerhardBerman 7:2f74dfd1d411 288 }
GerhardBerman 18:d2cfd07ae88a 289
GerhardBerman 7:2f74dfd1d411 290
GerhardBerman 24:393da1cc1fa8 291 void FeedbackControl1(float q1_ref, float q2_ref, float q1, float q2, float &motorValue1Out, float &motorValue2Out){
GerhardBerman 7:2f74dfd1d411 292
GerhardBerman 7:2f74dfd1d411 293 // linear feedback control
GerhardBerman 19:cba54636bd62 294 float q1_error = q1_ref - q1; //referencePosition1 - Position1; // proportional angular error in radians
GerhardBerman 19:cba54636bd62 295 float q2_error = q2_ref - q2; //referencePosition1 - Position1; // proportional angular error in radians
GerhardBerman 36:72f0913c5460 296 float Kp = 6; //potMeter2.read();
GerhardBerman 7:2f74dfd1d411 297
GerhardBerman 19:cba54636bd62 298 float q1IntError = q1IntError + q1_error*t_sample; // integrated error in radians
GerhardBerman 19:cba54636bd62 299 float q2IntError = q2IntError + q2_error*t_sample; // integrated error in radians
GerhardBerman 7:2f74dfd1d411 300 //float maxKi = 0.2;
GerhardBerman 34:96bcbddc7d2d 301 float Ki = 0.04*Kp; //0.01*Kp; //potMeter2.read();
GerhardBerman 7:2f74dfd1d411 302
GerhardBerman 27:456e8a47f815 303 float q1DerivativeError = (q1_error - q1_error_prev)/t_sample; // derivative of error in radians
GerhardBerman 19:cba54636bd62 304 float q2DerivativeError = (q2_error_prev + q2_error)/t_sample; // derivative of error in radians
GerhardBerman 7:2f74dfd1d411 305 //float maxKd = 0.2;
GerhardBerman 33:b09608fa69e9 306 float Kd = 0.0; //0.04*Kp; //potMeter2.read();
GerhardBerman 7:2f74dfd1d411 307
GerhardBerman 7:2f74dfd1d411 308 //scope.set(0,referencePosition1);
GerhardBerman 7:2f74dfd1d411 309 //scope.set(1,Position1);
GerhardBerman 7:2f74dfd1d411 310 //scope.set(2,Ki);
GerhardBerman 7:2f74dfd1d411 311 //scope.send();
GerhardBerman 7:2f74dfd1d411 312
GerhardBerman 23:3a4d5e19c20d 313 TotalError1 = q1_error * Kp + q1IntError * Ki + q1DerivativeError * Kd; //total controller output in radians = motor input
GerhardBerman 23:3a4d5e19c20d 314 TotalError2 = q2_error * Kp + q2IntError * Ki + q2DerivativeError * Kd; //total controller output in radians = motor input
11i 21:dd51d78c0732 315
GerhardBerman 33:b09608fa69e9 316 /*
GerhardBerman 33:b09608fa69e9 317 if (fabs(TotalError1) < TotalErrorMin) {
11i 21:dd51d78c0732 318 TotalError1=0;
11i 21:dd51d78c0732 319 }
11i 21:dd51d78c0732 320 else {
11i 21:dd51d78c0732 321 TotalError1=TotalError1;
11i 21:dd51d78c0732 322 }
GerhardBerman 33:b09608fa69e9 323 if (fabs(TotalError2) < TotalErrorMin) {
11i 21:dd51d78c0732 324 TotalError2=0;
11i 21:dd51d78c0732 325 }
11i 21:dd51d78c0732 326 else {
11i 21:dd51d78c0732 327 TotalError2=TotalError2;
11i 21:dd51d78c0732 328 }
GerhardBerman 33:b09608fa69e9 329 */
GerhardBerman 25:596255732b65 330 /*
GerhardBerman 25:596255732b65 331 DerTotalError1 = (TotalError1 - TotalError1_prev)/t_sample;
GerhardBerman 25:596255732b65 332 DerTotalError1 = (TotalError1 - TotalError1_prev)/t_sample;
GerhardBerman 25:596255732b65 333 motorValue1Out = DerTotalError1/MotorGain;
GerhardBerman 25:596255732b65 334 motorValue2Out = DerTotalError2/MotorGain;
GerhardBerman 25:596255732b65 335 */
GerhardBerman 25:596255732b65 336
11i 21:dd51d78c0732 337 motorValue1Out = TotalError1/MotorGain;
11i 21:dd51d78c0732 338 motorValue2Out = TotalError2/MotorGain;
11i 21:dd51d78c0732 339
GerhardBerman 33:b09608fa69e9 340 /*
GerhardBerman 29:caf3dd699617 341 scope.set(0,q1_ref);
GerhardBerman 29:caf3dd699617 342 scope.set(1,q1);
GerhardBerman 29:caf3dd699617 343 scope.set(2,q2_ref);
GerhardBerman 29:caf3dd699617 344 scope.set(3,q2);
GerhardBerman 29:caf3dd699617 345 scope.set(4,motorValue1Out);
GerhardBerman 29:caf3dd699617 346 scope.set(5,motorValue2Out);
GerhardBerman 29:caf3dd699617 347 scope.send();
GerhardBerman 33:b09608fa69e9 348 */
GerhardBerman 33:b09608fa69e9 349 /*
GerhardBerman 33:b09608fa69e9 350 pc.printf("E1: %f ", q1_error);
GerhardBerman 33:b09608fa69e9 351 pc.printf("IE1: %f ", q1IntError);
GerhardBerman 33:b09608fa69e9 352 pc.printf("DE1: %f ", q2DerivativeError);
GerhardBerman 33:b09608fa69e9 353 pc.printf("E2: %f ", q2_error);
GerhardBerman 33:b09608fa69e9 354 pc.printf("IE2: %f ", q2IntError);
GerhardBerman 33:b09608fa69e9 355 pc.printf("DE2: %f ", q2DerivativeError);
GerhardBerman 34:96bcbddc7d2d 356 */
GerhardBerman 33:b09608fa69e9 357 pc.printf("TE1: %f ", TotalError1);
GerhardBerman 33:b09608fa69e9 358 pc.printf("TE2: %f ", TotalError2);
GerhardBerman 33:b09608fa69e9 359 pc.printf("M1: %f ", motorValue1Out);
GerhardBerman 33:b09608fa69e9 360 pc.printf("M2: %f \r\n", motorValue2Out);
GerhardBerman 34:96bcbddc7d2d 361
GerhardBerman 19:cba54636bd62 362 q1_error_prev = q1_error;
GerhardBerman 19:cba54636bd62 363 q2_error_prev = q2_error;
GerhardBerman 25:596255732b65 364 TotalError1_prev = TotalError1;
GerhardBerman 33:b09608fa69e9 365 TotalError2_prev = TotalError2;
GerhardBerman 3:8caef4872b0c 366 }
GerhardBerman 3:8caef4872b0c 367
GerhardBerman 9:e4c34f5665a0 368 void SetMotor1(float motorValue1, float motorValue2)
GerhardBerman 3:8caef4872b0c 369 {
GerhardBerman 3:8caef4872b0c 370 // Given -1<=motorValue<=1, this sets the PWM and direction
GerhardBerman 3:8caef4872b0c 371 // bits for motor 1. Positive value makes motor rotating
GerhardBerman 3:8caef4872b0c 372 // clockwise. motorValues outside range are truncated to
GerhardBerman 3:8caef4872b0c 373 // within range
GerhardBerman 9:e4c34f5665a0 374 //control motor 1
GerhardBerman 15:9061cf7db23e 375 if (motorValue1 >=0) //clockwise rotation
GerhardBerman 19:cba54636bd62 376 {motor1DirectionPin=cw; //inverted due to opposite (to other motor) build-up in tower
GerhardBerman 9:e4c34f5665a0 377 //led1=1;
GerhardBerman 9:e4c34f5665a0 378 //led2=0;
GerhardBerman 3:8caef4872b0c 379 }
GerhardBerman 15:9061cf7db23e 380 else //counterclockwise rotation
GerhardBerman 19:cba54636bd62 381 {motor1DirectionPin=ccw; //inverted due to opposite (to other motor) build-up in tower
GerhardBerman 9:e4c34f5665a0 382 //led1=0;
GerhardBerman 9:e4c34f5665a0 383 //led2=1;
GerhardBerman 3:8caef4872b0c 384 }
GerhardBerman 29:caf3dd699617 385 if (fabs(motorValue1)>1){
GerhardBerman 29:caf3dd699617 386 motor1MagnitudePin = 1;
GerhardBerman 29:caf3dd699617 387 }
GerhardBerman 29:caf3dd699617 388 else{
GerhardBerman 29:caf3dd699617 389 motor1MagnitudePin = fabs(motorValue1); //fabs(motorValue1);
GerhardBerman 29:caf3dd699617 390 }
GerhardBerman 29:caf3dd699617 391
GerhardBerman 9:e4c34f5665a0 392 //control motor 2
GerhardBerman 15:9061cf7db23e 393 if (motorValue2 >=0) //clockwise rotation
GerhardBerman 14:725a608b6709 394 {motor2DirectionPin=ccw; //action is cw, due to faulty motor2DirectionPin (inverted)
GerhardBerman 10:45473f650198 395 //led1=1;
GerhardBerman 10:45473f650198 396 //led2=0;
GerhardBerman 7:2f74dfd1d411 397 }
GerhardBerman 15:9061cf7db23e 398 else //counterclockwise rotation
GerhardBerman 15:9061cf7db23e 399 {motor2DirectionPin=cw; //action is ccw, due to faulty motor2DirectionPin (inverted)
GerhardBerman 10:45473f650198 400 //led1=0;
GerhardBerman 10:45473f650198 401 //led2=1;
GerhardBerman 7:2f74dfd1d411 402 }
GerhardBerman 29:caf3dd699617 403 if (fabs(motorValue2)>1){
GerhardBerman 29:caf3dd699617 404 motor2MagnitudePin = 1;
GerhardBerman 29:caf3dd699617 405 }
GerhardBerman 29:caf3dd699617 406 else{
GerhardBerman 29:caf3dd699617 407 motor2MagnitudePin = fabs(motorValue2);
GerhardBerman 29:caf3dd699617 408 }
GerhardBerman 19:cba54636bd62 409 float ReadMagn1 = motor1MagnitudePin.read();
GerhardBerman 19:cba54636bd62 410 float ReadMagn2 = motor2MagnitudePin.read();
GerhardBerman 33:b09608fa69e9 411 //pc.printf("motor1Magnitude: %f \r\n", ReadMagn1);
GerhardBerman 33:b09608fa69e9 412 //pc.printf("motor2Magnitude: %f \r\n", ReadMagn2);
GerhardBerman 3:8caef4872b0c 413 }
GerhardBerman 3:8caef4872b0c 414
GerhardBerman 3:8caef4872b0c 415 void MeasureAndControl()
GerhardBerman 3:8caef4872b0c 416 {
GerhardBerman 9:e4c34f5665a0 417 // This function measures the EMG of both arms, calculates via IK what
GerhardBerman 24:393da1cc1fa8 418 // the joint positions should be, and controls the motor with
GerhardBerman 24:393da1cc1fa8 419 // a Feedback controller. This is called from a Ticker.
GerhardBerman 19:cba54636bd62 420 GetReferenceKinematics1(q1, q2, q1_ref, q2_ref);
GerhardBerman 24:393da1cc1fa8 421 FeedbackControl1( q1_ref, q2_ref, q1, q2, motorValue1, motorValue2);
GerhardBerman 9:e4c34f5665a0 422 SetMotor1(motorValue1, motorValue2);
GerhardBerman 3:8caef4872b0c 423 }
GerhardBerman 3:8caef4872b0c 424
GerhardBerman 3:8caef4872b0c 425 void TimeTrackerF(){
GerhardBerman 3:8caef4872b0c 426 //wait(1);
GerhardBerman 3:8caef4872b0c 427 //float Potmeter1 = potMeter1.read();
GerhardBerman 7:2f74dfd1d411 428 //float referencePosition1 = GetReferencePosition();
GerhardBerman 7:2f74dfd1d411 429 //pc.printf("TTReference Position: %d rad \r\n", referencePosition1);
GerhardBerman 3:8caef4872b0c 430 //pc.printf("TTPotmeter1, for refpos: %f \r\n", Potmeter1);
GerhardBerman 3:8caef4872b0c 431 //pc.printf("TTPotmeter2, Kp: %f \r\n", Potmeter2);
GerhardBerman 7:2f74dfd1d411 432 //pc.printf("TTCounts: %i \r\n", counts1);
GerhardBerman 3:8caef4872b0c 433 }
GerhardBerman 7:2f74dfd1d411 434
GerhardBerman 3:8caef4872b0c 435 /*
GerhardBerman 3:8caef4872b0c 436 void BiQuadFilter(){ //this function creates a BiQuad filter for the DerivativeCounts
GerhardBerman 3:8caef4872b0c 437 //double in=DerivativeCounts();
GerhardBerman 3:8caef4872b0c 438 bqcDerivativeCounts=bqc.step(DerivativeCounts);
GerhardBerman 3:8caef4872b0c 439 //return(bqcDerivativeCounts);
GerhardBerman 3:8caef4872b0c 440 }
GerhardBerman 9:e4c34f5665a0 441 */
GerhardBerman 6:3c4f3f2ce54f 442
GerhardBerman 0:43160ef59f9f 443 int main()
GerhardBerman 0:43160ef59f9f 444 {
GerhardBerman 0:43160ef59f9f 445 //Initialize
GerhardBerman 15:9061cf7db23e 446 //int led1val = led1.read();
GerhardBerman 15:9061cf7db23e 447 //int led2val = led2.read();
GerhardBerman 34:96bcbddc7d2d 448 pc.baud(115200);
GerhardBerman 34:96bcbddc7d2d 449 pc.printf("Test putty IK");
GerhardBerman 36:72f0913c5460 450 counts1 = Encoder1.getPulses(); // gives position of encoder
GerhardBerman 36:72f0913c5460 451 counts2 = Encoder2.getPulses(); // gives position of encoder
GerhardBerman 36:72f0913c5460 452 wait(10.0);
GerhardBerman 34:96bcbddc7d2d 453 MeasureTicker.attach(&MeasureTicker_act, 0.1f);
GerhardBerman 10:45473f650198 454 bqc.add(&bq1).add(&bq2);
GerhardBerman 10:45473f650198 455
GerhardBerman 0:43160ef59f9f 456 while(1)
GerhardBerman 0:43160ef59f9f 457 {
GerhardBerman 3:8caef4872b0c 458 if (MeasureTicker_go){
GerhardBerman 3:8caef4872b0c 459 MeasureTicker_go=false;
GerhardBerman 33:b09608fa69e9 460 ledgrn = 1;
GerhardBerman 33:b09608fa69e9 461 ledblue = 0;
GerhardBerman 3:8caef4872b0c 462 MeasureAndControl();
GerhardBerman 15:9061cf7db23e 463 counts1 = Encoder1.getPulses(); // gives position of encoder
GerhardBerman 15:9061cf7db23e 464 counts2 = Encoder2.getPulses(); // gives position of encoder
GerhardBerman 33:b09608fa69e9 465 //pc.printf("counts1: %i ", counts1);
GerhardBerman 33:b09608fa69e9 466 //pc.printf("counts2: %i \r\n", counts2);
GerhardBerman 33:b09608fa69e9 467 ledblue = 1;
GerhardBerman 33:b09608fa69e9 468 ledgrn = 0;
GerhardBerman 3:8caef4872b0c 469 }
GerhardBerman 10:45473f650198 470 /*
GerhardBerman 3:8caef4872b0c 471 if (BiQuadTicker_go){
GerhardBerman 3:8caef4872b0c 472 BiQuadTicker_go=false;
GerhardBerman 3:8caef4872b0c 473 BiQuadFilter();
GerhardBerman 3:8caef4872b0c 474 }
GerhardBerman 10:45473f650198 475 */
GerhardBerman 0:43160ef59f9f 476 }
GerhardBerman 0:43160ef59f9f 477 }