Totale script, 2 rotationele joints met middelpunt van swiffer als end-effector die verticaal en horizontaal wordt bestuurd middels EMG-signalen. Automatische kalibratie, grenshoeken

Dependencies:   HIDScope MODSERIAL QEI biquadFilter mbed

Committer:
willem_hoitzing
Date:
Fri Oct 28 10:36:03 2016 +0000
Revision:
0:e03285f8a410
Child:
1:078e96685ed3
InvKin+PID sloom, enigszins rechte lijnen; ; EMG control + knopjes om te simuleren; WERKT

Who changed what in which revision?

UserRevisionLine numberNew contents of line
willem_hoitzing 0:e03285f8a410 1 #include "stdio.h"
willem_hoitzing 0:e03285f8a410 2 #include "math.h"
willem_hoitzing 0:e03285f8a410 3 #include "mbed.h"
willem_hoitzing 0:e03285f8a410 4 #include "QEI.h"
willem_hoitzing 0:e03285f8a410 5 #include "MODSERIAL.h"
willem_hoitzing 0:e03285f8a410 6 #include "BiQuad.h"
willem_hoitzing 0:e03285f8a410 7 #include "HIDScope.h"
willem_hoitzing 0:e03285f8a410 8
willem_hoitzing 0:e03285f8a410 9 MODSERIAL pc(USBTX, USBRX);
willem_hoitzing 0:e03285f8a410 10 QEI wheel_M1 (D13, D12, NC, 32);
willem_hoitzing 0:e03285f8a410 11 QEI wheel_M2 (D10, D11, NC, 32);
willem_hoitzing 0:e03285f8a410 12 PwmOut pwm_M1 (D6);
willem_hoitzing 0:e03285f8a410 13 PwmOut pwm_M2 (D5);
willem_hoitzing 0:e03285f8a410 14 DigitalOut dir_M1 (D7);
willem_hoitzing 0:e03285f8a410 15 DigitalOut dir_M2 (D4);
willem_hoitzing 0:e03285f8a410 16
willem_hoitzing 0:e03285f8a410 17 Ticker emgticker;
willem_hoitzing 0:e03285f8a410 18 AnalogIn emgB(A0);
willem_hoitzing 0:e03285f8a410 19 AnalogIn emgT(A1);
willem_hoitzing 0:e03285f8a410 20 AnalogIn emgS(A2);
willem_hoitzing 0:e03285f8a410 21 HIDScope scope(3);
willem_hoitzing 0:e03285f8a410 22
willem_hoitzing 0:e03285f8a410 23 DigitalOut ledg (LED_GREEN);
willem_hoitzing 0:e03285f8a410 24 DigitalOut ledr (LED_RED);
willem_hoitzing 0:e03285f8a410 25 DigitalOut ledb (LED_BLUE);
willem_hoitzing 0:e03285f8a410 26 InterruptIn knop_biceps(SW2);
willem_hoitzing 0:e03285f8a410 27 InterruptIn knop_triceps(SW3);
willem_hoitzing 0:e03285f8a410 28 InterruptIn knop_switch(D9);
willem_hoitzing 0:e03285f8a410 29
willem_hoitzing 0:e03285f8a410 30 BiQuadChain filter1b;
willem_hoitzing 0:e03285f8a410 31 BiQuadChain filter2b;
willem_hoitzing 0:e03285f8a410 32 BiQuadChain filter1t;
willem_hoitzing 0:e03285f8a410 33 BiQuadChain filter2t;
willem_hoitzing 0:e03285f8a410 34 BiQuadChain filter1s;
willem_hoitzing 0:e03285f8a410 35 BiQuadChain filter2s;
willem_hoitzing 0:e03285f8a410 36
willem_hoitzing 0:e03285f8a410 37 BiQuad bq1b(8.5977e-01, -1.7195e+00, 8.5977e-01, -1.7347e+00, 7.6601e-01); // Notch + HP
willem_hoitzing 0:e03285f8a410 38 BiQuad bq2b(1.0000e+00, -1.6182e+00, 1.0000e+00, -1.5933e+00, 9.8217e-01); // Notch + HP
willem_hoitzing 0:e03285f8a410 39 BiQuad bq3b(1.0000e+00, -1.6182e+00, 1.0000e+00, -1.6143e+00 , 9.8260e-01); // Notch + HP
willem_hoitzing 0:e03285f8a410 40 BiQuad bq4b(3.4604e-04, 6.9208e-04, 3.4604e-04, -1.9467e+00, 9.4808e-01); // LP
willem_hoitzing 0:e03285f8a410 41
willem_hoitzing 0:e03285f8a410 42 BiQuad bq1t(8.5977e-01, -1.7195e+00, 8.5977e-01, -1.7347e+00, 7.6601e-01); // Notch + HP
willem_hoitzing 0:e03285f8a410 43 BiQuad bq2t(1.0000e+00, -1.6182e+00, 1.0000e+00, -1.5933e+00, 9.8217e-01); // Notch + HP
willem_hoitzing 0:e03285f8a410 44 BiQuad bq3t(1.0000e+00, -1.6182e+00, 1.0000e+00, -1.6143e+00 , 9.8260e-01); // Notch + HP
willem_hoitzing 0:e03285f8a410 45 BiQuad bq4t(3.4604e-04, 6.9208e-04, 3.4604e-04, -1.9467e+00, 9.4808e-01); // LP
willem_hoitzing 0:e03285f8a410 46
willem_hoitzing 0:e03285f8a410 47 BiQuad bq1s(8.5977e-01, -1.7195e+00, 8.5977e-01, -1.7347e+00, 7.6601e-01); // Notch + HP
willem_hoitzing 0:e03285f8a410 48 BiQuad bq2s(1.0000e+00, -1.6182e+00, 1.0000e+00, -1.5933e+00, 9.8217e-01); // Notch + HP
willem_hoitzing 0:e03285f8a410 49 BiQuad bq3s(1.0000e+00, -1.6182e+00, 1.0000e+00, -1.6143e+00 , 9.8260e-01); // Notch + HP
willem_hoitzing 0:e03285f8a410 50 BiQuad bq4s(3.4604e-04, 6.9208e-04, 3.4604e-04, -1.9467e+00, 9.4808e-01); // LP
willem_hoitzing 0:e03285f8a410 51
willem_hoitzing 0:e03285f8a410 52 const float threshold_biceps = 0.07;
willem_hoitzing 0:e03285f8a410 53 const float threshold_triceps = 0.07;
willem_hoitzing 0:e03285f8a410 54 const float threshold_switch = 0.05;
willem_hoitzing 0:e03285f8a410 55
willem_hoitzing 0:e03285f8a410 56 volatile float q1 = 0;
willem_hoitzing 0:e03285f8a410 57 volatile float q2 = 0;
willem_hoitzing 0:e03285f8a410 58 volatile float q1_begin;
willem_hoitzing 0:e03285f8a410 59 volatile float q2_begin;
willem_hoitzing 0:e03285f8a410 60 const float l1 = 0.3626;
willem_hoitzing 0:e03285f8a410 61 const float l2 = 0.420;
willem_hoitzing 0:e03285f8a410 62 volatile float q1_v;
willem_hoitzing 0:e03285f8a410 63 volatile float q2_v;
willem_hoitzing 0:e03285f8a410 64 volatile float q1_ref = 0;
willem_hoitzing 0:e03285f8a410 65 volatile float q2_ref = 0;
willem_hoitzing 0:e03285f8a410 66 volatile float q1_error = 0;
willem_hoitzing 0:e03285f8a410 67 volatile float q2_error = 0;
willem_hoitzing 0:e03285f8a410 68 volatile float q1_error_prev = 0;
willem_hoitzing 0:e03285f8a410 69 volatile float q2_error_prev = 0;
willem_hoitzing 0:e03285f8a410 70 volatile float q1DerivativeError = 0;
willem_hoitzing 0:e03285f8a410 71 volatile float q2DerivativeError = 0;
willem_hoitzing 0:e03285f8a410 72 volatile float q1IntError = 0;
willem_hoitzing 0:e03285f8a410 73 volatile float q2IntError = 0;
willem_hoitzing 0:e03285f8a410 74 volatile float TotalError1= 0;
willem_hoitzing 0:e03285f8a410 75 volatile float TotalError2= 0;
willem_hoitzing 0:e03285f8a410 76 float ctrlOutput_M1 = 0;
willem_hoitzing 0:e03285f8a410 77 float ctrlOutput_M2 = 0;
willem_hoitzing 0:e03285f8a410 78 volatile float vx;
willem_hoitzing 0:e03285f8a410 79 volatile float vy;
willem_hoitzing 0:e03285f8a410 80 volatile bool translatie_richting = true; //true is verticaal, false is horizontaal
willem_hoitzing 0:e03285f8a410 81
willem_hoitzing 0:e03285f8a410 82 const float TS = 0.02;
willem_hoitzing 0:e03285f8a410 83 const float MotorGain_M1 = 4.3; // bij pwm = 1 draait (losse) motor met 4.3 rad/s -> gemeten
willem_hoitzing 0:e03285f8a410 84 const float MotorGain_M2 = 4.7; // gemeten
willem_hoitzing 0:e03285f8a410 85
willem_hoitzing 0:e03285f8a410 86 Ticker update_encoder_ticker;
willem_hoitzing 0:e03285f8a410 87 volatile bool go_flag_update_encoder = false;
willem_hoitzing 0:e03285f8a410 88 void flag_update_encoder()
willem_hoitzing 0:e03285f8a410 89 {
willem_hoitzing 0:e03285f8a410 90 go_flag_update_encoder = true;
willem_hoitzing 0:e03285f8a410 91 }
willem_hoitzing 0:e03285f8a410 92
willem_hoitzing 0:e03285f8a410 93 void update_encoder()
willem_hoitzing 0:e03285f8a410 94 {
willem_hoitzing 0:e03285f8a410 95 //q1 = wheel_M1.getPulses()/(1334.355/2);
willem_hoitzing 0:e03285f8a410 96 //q2 = wheel_M2.getPulses()/(1334.355/2);
willem_hoitzing 0:e03285f8a410 97 //pc.printf("q1 = %f \tq1_ref = %f \tq2 = %f \tq2_ref = %f \ttotalerr1 = %f \ttotalerr2 = %f\n\r",q1, q1_ref,q2,q2_ref,TotalError1,TotalError2);
willem_hoitzing 0:e03285f8a410 98 pc.printf("vx = %f \tvy = %f \tq1_r = %f \tq2_r = %f \tq1 = %f \tq2 = %f \tpwm_M1 = %f \tpwm_M2 = %f\n\r",vx,vy,q1_ref,q2_ref,q1,q2,pwm_M1.read(),pwm_M2.read());
willem_hoitzing 0:e03285f8a410 99 //pc.printf("q1_err = %0.9f \tq2_err = %0.9f \tq1IntErr = %0.9f \tq2IntErr = %0.9f \tTotErr1 = %0.9f \tTotErr2 = %0.9f\n\r",q1_error,q2_error,q1IntError,q2IntError,TotalError1,TotalError2);
willem_hoitzing 0:e03285f8a410 100 }
willem_hoitzing 0:e03285f8a410 101
willem_hoitzing 0:e03285f8a410 102 Ticker PIDcontrol;
willem_hoitzing 0:e03285f8a410 103 volatile bool go_flag_controller = false;
willem_hoitzing 0:e03285f8a410 104
willem_hoitzing 0:e03285f8a410 105 void flag_controller()
willem_hoitzing 0:e03285f8a410 106 {
willem_hoitzing 0:e03285f8a410 107 go_flag_controller = true;
willem_hoitzing 0:e03285f8a410 108 }
willem_hoitzing 0:e03285f8a410 109
willem_hoitzing 0:e03285f8a410 110 volatile bool active_PID_ticker = false;
willem_hoitzing 0:e03285f8a410 111
willem_hoitzing 0:e03285f8a410 112 void begin_hoeken()
willem_hoitzing 0:e03285f8a410 113 {
willem_hoitzing 0:e03285f8a410 114 wait(1);
willem_hoitzing 0:e03285f8a410 115 q1_ref = wheel_M1.getPulses()/(1334.355/2);
willem_hoitzing 0:e03285f8a410 116 q2_ref = wheel_M2.getPulses()/(1334.355/2);
willem_hoitzing 0:e03285f8a410 117 active_PID_ticker = true;
willem_hoitzing 0:e03285f8a410 118 }
willem_hoitzing 0:e03285f8a410 119
willem_hoitzing 0:e03285f8a410 120 void initialize()
willem_hoitzing 0:e03285f8a410 121 {
willem_hoitzing 0:e03285f8a410 122 dir_M1 = 0; //ccw
willem_hoitzing 0:e03285f8a410 123 dir_M2 = 1; //cw
willem_hoitzing 0:e03285f8a410 124 while (q1 < 20*2*3.1415/360) {
willem_hoitzing 0:e03285f8a410 125 q1 = wheel_M1.getPulses()/(1334.355/2);
willem_hoitzing 0:e03285f8a410 126 pwm_M1 = 0.05;
willem_hoitzing 0:e03285f8a410 127 wait(0.005f);
willem_hoitzing 0:e03285f8a410 128 }
willem_hoitzing 0:e03285f8a410 129 pwm_M1 = 0;
willem_hoitzing 0:e03285f8a410 130
willem_hoitzing 0:e03285f8a410 131 while (q2 > -45*2*3.1415/360) {
willem_hoitzing 0:e03285f8a410 132 q2 = wheel_M2.getPulses()/(1334.355/2);
willem_hoitzing 0:e03285f8a410 133 pwm_M2 = 0.05;
willem_hoitzing 0:e03285f8a410 134 wait(0.005f);
willem_hoitzing 0:e03285f8a410 135 }
willem_hoitzing 0:e03285f8a410 136 pwm_M2 = 0;
willem_hoitzing 0:e03285f8a410 137 ledg = !ledg;
willem_hoitzing 0:e03285f8a410 138 begin_hoeken();
willem_hoitzing 0:e03285f8a410 139 }
willem_hoitzing 0:e03285f8a410 140
willem_hoitzing 0:e03285f8a410 141 void biceps()
willem_hoitzing 0:e03285f8a410 142 {
willem_hoitzing 0:e03285f8a410 143 q1IntError = 0;
willem_hoitzing 0:e03285f8a410 144 q2IntError = 0;
willem_hoitzing 0:e03285f8a410 145 q1_error_prev = 0;
willem_hoitzing 0:e03285f8a410 146 q2_error_prev = 0;
willem_hoitzing 0:e03285f8a410 147 if (translatie_richting == true) { // verticaal / up
willem_hoitzing 0:e03285f8a410 148 vx = 0;
willem_hoitzing 0:e03285f8a410 149 vy = 0.1;
willem_hoitzing 0:e03285f8a410 150 } else { // horizontaal / right
willem_hoitzing 0:e03285f8a410 151 vx = 0.1;
willem_hoitzing 0:e03285f8a410 152 vy = 0;
willem_hoitzing 0:e03285f8a410 153 }
willem_hoitzing 0:e03285f8a410 154 }
willem_hoitzing 0:e03285f8a410 155
willem_hoitzing 0:e03285f8a410 156 void triceps()
willem_hoitzing 0:e03285f8a410 157 {
willem_hoitzing 0:e03285f8a410 158 q1IntError = 0;
willem_hoitzing 0:e03285f8a410 159 q2IntError = 0;
willem_hoitzing 0:e03285f8a410 160 q1_error_prev = 0;
willem_hoitzing 0:e03285f8a410 161 q2_error_prev = 0;
willem_hoitzing 0:e03285f8a410 162 if (translatie_richting == true) { // verticaal / down
willem_hoitzing 0:e03285f8a410 163 vx = 0;
willem_hoitzing 0:e03285f8a410 164 vy = -0.1;
willem_hoitzing 0:e03285f8a410 165 } else { // horizontaal / left
willem_hoitzing 0:e03285f8a410 166 vx = -0.1;
willem_hoitzing 0:e03285f8a410 167 vy = 0;
willem_hoitzing 0:e03285f8a410 168 }
willem_hoitzing 0:e03285f8a410 169
willem_hoitzing 0:e03285f8a410 170 }
willem_hoitzing 0:e03285f8a410 171
willem_hoitzing 0:e03285f8a410 172 void switcher()
willem_hoitzing 0:e03285f8a410 173 {
willem_hoitzing 0:e03285f8a410 174 if ( (vx == 0) && (vy == 0) && (translatie_richting == true) ) {
willem_hoitzing 0:e03285f8a410 175 translatie_richting = false;
willem_hoitzing 0:e03285f8a410 176 } else if ( (vx == 0) && (vy == 0) && (translatie_richting == false) ) {
willem_hoitzing 0:e03285f8a410 177 translatie_richting = true;
willem_hoitzing 0:e03285f8a410 178 } else {
willem_hoitzing 0:e03285f8a410 179 vx = 0;
willem_hoitzing 0:e03285f8a410 180 vy = 0;
willem_hoitzing 0:e03285f8a410 181 q1IntError = 0;
willem_hoitzing 0:e03285f8a410 182 q2IntError = 0;
willem_hoitzing 0:e03285f8a410 183 q1_error_prev = 0;
willem_hoitzing 0:e03285f8a410 184 q2_error_prev = 0;
willem_hoitzing 0:e03285f8a410 185 }
willem_hoitzing 0:e03285f8a410 186
willem_hoitzing 0:e03285f8a410 187 if (translatie_richting == 1) {
willem_hoitzing 0:e03285f8a410 188 ledr = 1; // blauw - verticaal
willem_hoitzing 0:e03285f8a410 189 ledg = 1;
willem_hoitzing 0:e03285f8a410 190 ledb = 0;
willem_hoitzing 0:e03285f8a410 191 } else {
willem_hoitzing 0:e03285f8a410 192 ledr = 0; // rood - horizontaal
willem_hoitzing 0:e03285f8a410 193 ledg = 1;
willem_hoitzing 0:e03285f8a410 194 ledb = 1;
willem_hoitzing 0:e03285f8a410 195 }
willem_hoitzing 0:e03285f8a410 196 }
willem_hoitzing 0:e03285f8a410 197
willem_hoitzing 0:e03285f8a410 198 Ticker switch_activate_ticker;
willem_hoitzing 0:e03285f8a410 199 volatile bool switch_active = true;
willem_hoitzing 0:e03285f8a410 200 void switch_activate()
willem_hoitzing 0:e03285f8a410 201 {
willem_hoitzing 0:e03285f8a410 202 switch_active = true;
willem_hoitzing 0:e03285f8a410 203 }
willem_hoitzing 0:e03285f8a410 204
willem_hoitzing 0:e03285f8a410 205 volatile bool go_flag_emgsample = false;
willem_hoitzing 0:e03285f8a410 206 void flag_emgsample()
willem_hoitzing 0:e03285f8a410 207 {
willem_hoitzing 0:e03285f8a410 208 go_flag_emgsample = true;
willem_hoitzing 0:e03285f8a410 209 }
willem_hoitzing 0:e03285f8a410 210
willem_hoitzing 0:e03285f8a410 211 void emgsample()
willem_hoitzing 0:e03285f8a410 212 {
willem_hoitzing 0:e03285f8a410 213 float bEMG_raw = emgB.read();
willem_hoitzing 0:e03285f8a410 214 float bEMG_HPfilt = filter1b.step( bEMG_raw );
willem_hoitzing 0:e03285f8a410 215 float bEMG_rect = abs(bEMG_HPfilt);
willem_hoitzing 0:e03285f8a410 216 float bEMG_filt = filter2b.step(bEMG_rect);
willem_hoitzing 0:e03285f8a410 217
willem_hoitzing 0:e03285f8a410 218 float tEMG_raw = emgT.read();
willem_hoitzing 0:e03285f8a410 219 float tEMG_HPfilt = filter1t.step( tEMG_raw );
willem_hoitzing 0:e03285f8a410 220 float tEMG_rect = abs(tEMG_HPfilt);
willem_hoitzing 0:e03285f8a410 221 float tEMG_filt = filter2t.step(tEMG_rect);
willem_hoitzing 0:e03285f8a410 222
willem_hoitzing 0:e03285f8a410 223 float sEMG_raw = emgS.read();
willem_hoitzing 0:e03285f8a410 224 float sEMG_HPfilt = filter1s.step( sEMG_raw );
willem_hoitzing 0:e03285f8a410 225 float sEMG_rect = abs(sEMG_HPfilt);
willem_hoitzing 0:e03285f8a410 226 float sEMG_filt = filter2s.step(sEMG_rect);
willem_hoitzing 0:e03285f8a410 227
willem_hoitzing 0:e03285f8a410 228 scope.set(0, bEMG_filt);
willem_hoitzing 0:e03285f8a410 229 scope.set(1, tEMG_filt);
willem_hoitzing 0:e03285f8a410 230 scope.set(2, sEMG_filt);
willem_hoitzing 0:e03285f8a410 231 scope.send();
willem_hoitzing 0:e03285f8a410 232
willem_hoitzing 0:e03285f8a410 233 // motor aansturing
willem_hoitzing 0:e03285f8a410 234 if (sEMG_filt > threshold_switch) {
willem_hoitzing 0:e03285f8a410 235 if (switch_active == true) {
willem_hoitzing 0:e03285f8a410 236 switcher();
willem_hoitzing 0:e03285f8a410 237 switch_active = false;
willem_hoitzing 0:e03285f8a410 238 switch_activate_ticker.attach(&switch_activate, 0.5f);
willem_hoitzing 0:e03285f8a410 239 }
willem_hoitzing 0:e03285f8a410 240 } else if (tEMG_filt > threshold_triceps) {
willem_hoitzing 0:e03285f8a410 241 triceps();
willem_hoitzing 0:e03285f8a410 242 } else if (bEMG_filt > threshold_biceps) {
willem_hoitzing 0:e03285f8a410 243 biceps();
willem_hoitzing 0:e03285f8a410 244 }
willem_hoitzing 0:e03285f8a410 245 }
willem_hoitzing 0:e03285f8a410 246
willem_hoitzing 0:e03285f8a410 247 Ticker update_ref_ticker;
willem_hoitzing 0:e03285f8a410 248 volatile float J_1;
willem_hoitzing 0:e03285f8a410 249 volatile float J_2;
willem_hoitzing 0:e03285f8a410 250 volatile float J_3;
willem_hoitzing 0:e03285f8a410 251 volatile float J_4;
willem_hoitzing 0:e03285f8a410 252 volatile bool go_flag_update_ref = false;
willem_hoitzing 0:e03285f8a410 253 void flag_update_ref()
willem_hoitzing 0:e03285f8a410 254 {
willem_hoitzing 0:e03285f8a410 255 go_flag_update_ref = true;
willem_hoitzing 0:e03285f8a410 256 }
willem_hoitzing 0:e03285f8a410 257
willem_hoitzing 0:e03285f8a410 258 void update_ref()
willem_hoitzing 0:e03285f8a410 259 {
willem_hoitzing 0:e03285f8a410 260 q1 = wheel_M1.getPulses() / (1334.355/2); // rad
willem_hoitzing 0:e03285f8a410 261 q2 = wheel_M2.getPulses() / (1334.355/2);
willem_hoitzing 0:e03285f8a410 262
willem_hoitzing 0:e03285f8a410 263 J_1 = -(l2*sin(q1 + q2))/(l2*sin(q1 + q2)*(l2*cos(q1 + q2) + l1*cos(q1)) - l2*cos(q1 + q2)*(l2*sin(q1 + q2) + l1*sin(q1)));
willem_hoitzing 0:e03285f8a410 264 J_2 = (l2*cos(q1 + q2))/(l2*sin(q1 + q2)*(l2*cos(q1 + q2) + l1*cos(q1)) - l2*cos(q1 + q2)*(l2*sin(q1 + q2) + l1*sin(q1)));
willem_hoitzing 0:e03285f8a410 265 J_3 = (l2*sin(q1 + q2) + l1*sin(q1))/(l2*sin(q1 + q2)*(l2*cos(q1 + q2) + l1*cos(q1)) - l2*cos(q1 + q2)*(l2*sin(q1 + q2) + l1*sin(q1)));
willem_hoitzing 0:e03285f8a410 266 J_4 = -(l2*cos(q1 + q2) + l1*cos(q1))/(l2*sin(q1 + q2)*(l2*cos(q1 + q2) + l1*cos(q1)) - l2*cos(q1 + q2)*(l2*sin(q1 + q2) + l1*sin(q1)));
willem_hoitzing 0:e03285f8a410 267
willem_hoitzing 0:e03285f8a410 268 q1_v = J_1 * vx + J_2 * vy;
willem_hoitzing 0:e03285f8a410 269 q2_v = J_3 * vx + J_4 * vy;
willem_hoitzing 0:e03285f8a410 270
willem_hoitzing 0:e03285f8a410 271 if ( (q1 > (90*2*3.1415/360)) && (q1_v > 0 ) ) { // WAARDES VINDEN 0.8726 (50 graden)
willem_hoitzing 0:e03285f8a410 272 q1_v = 0;
willem_hoitzing 0:e03285f8a410 273 q2_v = 0;
willem_hoitzing 0:e03285f8a410 274 } else if ( (q1 < -(90*2*3.1415/360)) && (q1_v < 0) ) {
willem_hoitzing 0:e03285f8a410 275 q1_v = 0;
willem_hoitzing 0:e03285f8a410 276 q2_v = 0;
willem_hoitzing 0:e03285f8a410 277 } else if ( (q2 < (-140*2*3.1415/360)) && (q2_v < 0) ) { // WAARDES VINDEN -2.4434 (-140 graden) --> werkelijke max -2.672452
willem_hoitzing 0:e03285f8a410 278 q1_v = 0;
willem_hoitzing 0:e03285f8a410 279 q2_v = 0;
willem_hoitzing 0:e03285f8a410 280 } else if ( (q2 > 0) && (q2_v > 0) ) {
willem_hoitzing 0:e03285f8a410 281 q1_v = 0;
willem_hoitzing 0:e03285f8a410 282 q2_v = 0;
willem_hoitzing 0:e03285f8a410 283 }
willem_hoitzing 0:e03285f8a410 284
willem_hoitzing 0:e03285f8a410 285 q1_ref = q1 + q1_v*TS;
willem_hoitzing 0:e03285f8a410 286 q2_ref = q2 + q2_v*TS;
willem_hoitzing 0:e03285f8a410 287 }
willem_hoitzing 0:e03285f8a410 288
willem_hoitzing 0:e03285f8a410 289 void PID(float q1,float q1_ref,float q2,float q2_ref,float TS,float &ctrlOutput_M1, float &ctrlOutput_M2)
willem_hoitzing 0:e03285f8a410 290 {
willem_hoitzing 0:e03285f8a410 291 // linear feedback control
willem_hoitzing 0:e03285f8a410 292 q1_error = q1_ref - q1; //referencePosition1 - Position1; // proportional angular error in radians
willem_hoitzing 0:e03285f8a410 293 q2_error = q2_ref - q2; //referencePosition1 - Position1; // proportional angular error in radians
willem_hoitzing 0:e03285f8a410 294 float Kp = 10;
willem_hoitzing 0:e03285f8a410 295
willem_hoitzing 0:e03285f8a410 296 q1IntError = q1IntError + q1_error*TS; // integrated error in radians
willem_hoitzing 0:e03285f8a410 297 q2IntError = q2IntError + q2_error*TS; // integrated error in radians
willem_hoitzing 0:e03285f8a410 298 float Ki = 1;
willem_hoitzing 0:e03285f8a410 299
willem_hoitzing 0:e03285f8a410 300 q1DerivativeError = (q1_error - q1_error_prev)/TS; // derivative of error in radians
willem_hoitzing 0:e03285f8a410 301 q2DerivativeError = (q2_error - q2_error_prev)/TS; // derivative of error in radians
willem_hoitzing 0:e03285f8a410 302 float Kd = 0;
willem_hoitzing 0:e03285f8a410 303
willem_hoitzing 0:e03285f8a410 304 TotalError1 = (q1_error * Kp) + (q1IntError * Ki) + (q1DerivativeError * Kd); //total controller output = motor input
willem_hoitzing 0:e03285f8a410 305 TotalError2 = (q2_error * Kp) + (q2IntError * Ki) + (q2DerivativeError * Kd); //total controller output = motor input
willem_hoitzing 0:e03285f8a410 306
willem_hoitzing 0:e03285f8a410 307 ctrlOutput_M1 = TotalError1/MotorGain_M1;
willem_hoitzing 0:e03285f8a410 308 ctrlOutput_M2 = TotalError2/MotorGain_M2;
willem_hoitzing 0:e03285f8a410 309
willem_hoitzing 0:e03285f8a410 310 q1_error_prev = q1_error;
willem_hoitzing 0:e03285f8a410 311 q2_error_prev = q2_error;
willem_hoitzing 0:e03285f8a410 312 }
willem_hoitzing 0:e03285f8a410 313
willem_hoitzing 0:e03285f8a410 314 void Controller()
willem_hoitzing 0:e03285f8a410 315 {
willem_hoitzing 0:e03285f8a410 316 PID(q1,q1_ref,q2,q2_ref,TS,ctrlOutput_M1,ctrlOutput_M2);
willem_hoitzing 0:e03285f8a410 317
willem_hoitzing 0:e03285f8a410 318 if (ctrlOutput_M1 < 0) {
willem_hoitzing 0:e03285f8a410 319 dir_M1 = 1;
willem_hoitzing 0:e03285f8a410 320 } else {
willem_hoitzing 0:e03285f8a410 321 dir_M1 = 0;
willem_hoitzing 0:e03285f8a410 322 }
willem_hoitzing 0:e03285f8a410 323 pwm_M1 = abs(ctrlOutput_M1);
willem_hoitzing 0:e03285f8a410 324 if (pwm_M1 <= 0) {
willem_hoitzing 0:e03285f8a410 325 pwm_M1 = 0;
willem_hoitzing 0:e03285f8a410 326 } else {
willem_hoitzing 0:e03285f8a410 327 pwm_M1 = pwm_M1 + 0.05;
willem_hoitzing 0:e03285f8a410 328 }
willem_hoitzing 0:e03285f8a410 329
willem_hoitzing 0:e03285f8a410 330 if (ctrlOutput_M2 < 0) {
willem_hoitzing 0:e03285f8a410 331 dir_M2 = 1;
willem_hoitzing 0:e03285f8a410 332 } else {
willem_hoitzing 0:e03285f8a410 333 dir_M2 = 0;
willem_hoitzing 0:e03285f8a410 334 }
willem_hoitzing 0:e03285f8a410 335 pwm_M2 = abs(ctrlOutput_M2);
willem_hoitzing 0:e03285f8a410 336 if (pwm_M2 <= 0) {
willem_hoitzing 0:e03285f8a410 337 pwm_M2 = 0;
willem_hoitzing 0:e03285f8a410 338 } else {
willem_hoitzing 0:e03285f8a410 339 pwm_M2 = pwm_M2 + 0.05;
willem_hoitzing 0:e03285f8a410 340 }
willem_hoitzing 0:e03285f8a410 341 }
willem_hoitzing 0:e03285f8a410 342
willem_hoitzing 0:e03285f8a410 343 int main()
willem_hoitzing 0:e03285f8a410 344 {
willem_hoitzing 0:e03285f8a410 345 ledr = 1;
willem_hoitzing 0:e03285f8a410 346 ledg = 1;
willem_hoitzing 0:e03285f8a410 347 ledb = 0;
willem_hoitzing 0:e03285f8a410 348 pc.baud(115200);
willem_hoitzing 0:e03285f8a410 349 wheel_M1.reset();
willem_hoitzing 0:e03285f8a410 350 wheel_M2.reset();
willem_hoitzing 0:e03285f8a410 351 filter1b.add(&bq1b).add(&bq2b).add(&bq3b);
willem_hoitzing 0:e03285f8a410 352 filter2b.add(&bq4b);
willem_hoitzing 0:e03285f8a410 353 filter1t.add(&bq1t).add(&bq2t).add(&bq3t);
willem_hoitzing 0:e03285f8a410 354 filter2t.add(&bq4t);
willem_hoitzing 0:e03285f8a410 355 filter1s.add(&bq1s).add(&bq2s).add(&bq3s);
willem_hoitzing 0:e03285f8a410 356 filter2s.add(&bq4s);
willem_hoitzing 0:e03285f8a410 357 knop_biceps.rise(&biceps);
willem_hoitzing 0:e03285f8a410 358 knop_triceps.rise(&triceps);
willem_hoitzing 0:e03285f8a410 359 knop_switch.rise(&switcher);
willem_hoitzing 0:e03285f8a410 360
willem_hoitzing 0:e03285f8a410 361 // flag functions/tickers
willem_hoitzing 0:e03285f8a410 362 emgticker.attach(&emgsample, 0.002f); // 500 Hz --> moet kloppen met frequentie gebruikt voor filter coefficienten
willem_hoitzing 0:e03285f8a410 363 update_encoder_ticker.attach(&flag_update_encoder, TS);
willem_hoitzing 0:e03285f8a410 364 update_ref_ticker.attach(&flag_update_ref, TS);
willem_hoitzing 0:e03285f8a410 365 // initialize -> beginposities
willem_hoitzing 0:e03285f8a410 366 initialize();
willem_hoitzing 0:e03285f8a410 367
willem_hoitzing 0:e03285f8a410 368 if (active_PID_ticker == true) {
willem_hoitzing 0:e03285f8a410 369 PIDcontrol.attach(&flag_controller, TS);
willem_hoitzing 0:e03285f8a410 370 }
willem_hoitzing 0:e03285f8a410 371
willem_hoitzing 0:e03285f8a410 372 while(1) {
willem_hoitzing 0:e03285f8a410 373 // sample EMG
willem_hoitzing 0:e03285f8a410 374 if (go_flag_emgsample == true) {
willem_hoitzing 0:e03285f8a410 375 go_flag_emgsample = false;
willem_hoitzing 0:e03285f8a410 376 emgsample();
willem_hoitzing 0:e03285f8a410 377 }
willem_hoitzing 0:e03285f8a410 378 // update encoder
willem_hoitzing 0:e03285f8a410 379 if (go_flag_update_encoder == true) {
willem_hoitzing 0:e03285f8a410 380 go_flag_update_encoder = false;
willem_hoitzing 0:e03285f8a410 381 update_encoder();
willem_hoitzing 0:e03285f8a410 382 }
willem_hoitzing 0:e03285f8a410 383 // update joint positions/velocities
willem_hoitzing 0:e03285f8a410 384 if (go_flag_update_ref == true) {
willem_hoitzing 0:e03285f8a410 385 go_flag_update_ref = false;
willem_hoitzing 0:e03285f8a410 386 update_ref();
willem_hoitzing 0:e03285f8a410 387 }
willem_hoitzing 0:e03285f8a410 388 // controller M1+M2
willem_hoitzing 0:e03285f8a410 389 if (go_flag_controller == true) {
willem_hoitzing 0:e03285f8a410 390 go_flag_controller = false;
willem_hoitzing 0:e03285f8a410 391 Controller();
willem_hoitzing 0:e03285f8a410 392 }
willem_hoitzing 0:e03285f8a410 393 }
willem_hoitzing 0:e03285f8a410 394 }