EMG added to main IK program. No errors, not yet tested

Dependencies:   HIDScope MODSERIAL QEI biquadFilter mbed

Fork of prog_forwardkin_feedback_copy3 by Gerhard Berman

Committer:
GerhardBerman
Date:
Wed Oct 26 09:24:38 2016 +0000
Revision:
24:393da1cc1fa8
Parent:
23:3a4d5e19c20d
Child:
25:596255732b65
Error fixed

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