Version for EMG Threshold finding

Dependencies:   HIDScope MODSERIAL QEI biquadFilter mbed

Fork of prog_BioRobotics_Group9_StampRobot by Gerhard Berman

Committer:
GerhardBerman
Date:
Fri Oct 28 09:31:08 2016 +0000
Revision:
30:676ecd59467a
Parent:
29:caf3dd699617
Child:
31:880ebd2e8145
Child:
32:3b00eafcf168
Added MotorSpeedGain to make motors faster. Angles are not ending up at reference angles

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