Version for EMG Threshold finding

Dependencies:   HIDScope MODSERIAL QEI biquadFilter mbed

Fork of prog_BioRobotics_Group9_StampRobot by Gerhard Berman

Committer:
GerhardBerman
Date:
Tue Nov 01 15:47:40 2016 +0000
Revision:
35:a21c1cab8086
Parent:
34:96bcbddc7d2d
PID Filter implemented. Motors working, but initial TotalError is not zero -> spontaneous iniitial action. PID parameters are not yet perfect.

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