Version for EMG Threshold finding

Dependencies:   HIDScope MODSERIAL QEI biquadFilter mbed

Fork of prog_BioRobotics_Group9_StampRobot by Gerhard Berman

Committer:
GerhardBerman
Date:
Thu Nov 03 15:09:14 2016 +0000
Revision:
39:cc7754330c26
Parent:
38:e58bab07275e
Child:
40:9ecaab27acde
Robot working, but slow and not reaching reference positions.

Who changed what in which revision?

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