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