testcode pid

Dependencies:   HIDScope MODSERIAL QEI biquadFilter mbed

Fork of testPID by Martijn Kern

Committer:
Vigilance88
Date:
Wed Oct 14 13:04:54 2015 +0000
Revision:
24:56db31267f10
Parent:
23:e9b1b426cde6
Child:
25:49ccdc98639a
calibrate verbeterd

Who changed what in which revision?

UserRevisionLine numberNew contents of line
vsluiter 0:32bb76391d89 1 #include "mbed.h"
vsluiter 11:ce72ec658a95 2 #include "HIDScope.h"
Vigilance88 18:44905b008f44 3 #include "MODSERIAL.h"
Vigilance88 18:44905b008f44 4 #include "biquadFilter.h"
Vigilance88 18:44905b008f44 5 #include "QEI.h"
Vigilance88 21:d6a46315d5f5 6 #include "math.h"
Vigilance88 21:d6a46315d5f5 7
Vigilance88 21:d6a46315d5f5 8 /*--------------------------------------------------------------------------------------------------------------------
Vigilance88 21:d6a46315d5f5 9 -------------------------------- BIOROBOTICS GROUP 14 ----------------------------------------------------------------
Vigilance88 21:d6a46315d5f5 10 --------------------------------------------------------------------------------------------------------------------*/
vsluiter 0:32bb76391d89 11
Vigilance88 18:44905b008f44 12 //Define important constants in memory
Vigilance88 21:d6a46315d5f5 13 #define PI 3.14159265
Vigilance88 18:44905b008f44 14 #define SAMPLE_RATE 0.002 //500 Hz EMG sample rate
Vigilance88 18:44905b008f44 15 #define CONTROL_RATE 0.01 //100 Hz Control rate
Vigilance88 21:d6a46315d5f5 16 #define ENCODER1_CPR 4200 //encoders have 64 (X4), 32 (X2) counts per revolution of motor shaft
Vigilance88 21:d6a46315d5f5 17 #define ENCODER2_CPR 4200 //gearbox 1:131.25 -> 4200 counts per revolution of the output shaft (X2),
Vigilance88 18:44905b008f44 18
Vigilance88 21:d6a46315d5f5 19 /*--------------------------------------------------------------------------------------------------------------------
Vigilance88 21:d6a46315d5f5 20 ---- OBJECTS ---------------------------------------------------------------------------------------------------------
Vigilance88 21:d6a46315d5f5 21 --------------------------------------------------------------------------------------------------------------------*/
Vigilance88 21:d6a46315d5f5 22
Vigilance88 18:44905b008f44 23 MODSERIAL pc(USBTX,USBRX); //serial communication
Vigilance88 18:44905b008f44 24 DigitalIn button(PTA1); //buttons
Vigilance88 18:44905b008f44 25 DigitalIn button1(PTB9); //
Vigilance88 18:44905b008f44 26
Vigilance88 21:d6a46315d5f5 27 //EMG shields
Vigilance88 18:44905b008f44 28 AnalogIn emg1(A0); //Analog input - Biceps EMG
Vigilance88 18:44905b008f44 29 AnalogIn emg2(A1); //Analog input - Triceps EMG
Vigilance88 18:44905b008f44 30 AnalogIn emg3(A2); //Analog input - Flexor EMG
Vigilance88 18:44905b008f44 31 AnalogIn emg4(A3); //Analog input - Extensor EMG
Vigilance88 18:44905b008f44 32
Vigilance88 18:44905b008f44 33 Ticker sample_timer; //Ticker for EMG sampling
Vigilance88 18:44905b008f44 34 Ticker control_timer; //Ticker for control loop
Vigilance88 18:44905b008f44 35 HIDScope scope(4); //Scope 4 channels
Vigilance88 18:44905b008f44 36
Vigilance88 18:44905b008f44 37 // AnalogIn potmeter(A4); //potmeters
Vigilance88 18:44905b008f44 38 // AnalogIn potmeter2(A5); //
Vigilance88 18:44905b008f44 39
Vigilance88 21:d6a46315d5f5 40 //Encoders
Vigilance88 18:44905b008f44 41 QEI Encoder1(D13,D12,NC,32); //channel A and B from encoder, counts = Encoder.getPulses();
Vigilance88 18:44905b008f44 42 QEI Encoder2(D10,D9,NC,32); //channel A and B from encoder,
Vigilance88 21:d6a46315d5f5 43
Vigilance88 21:d6a46315d5f5 44 //Speed and Direction of motors - D4 (dir) and D5(speed) = motor 2, D7(dir) and D6(speed) = motor 1
Vigilance88 21:d6a46315d5f5 45 PwmOut pwm_motor1(D6); //PWM motor 1
Vigilance88 21:d6a46315d5f5 46 PwmOut pwm_motor2(D5); //PWM motor 2
Vigilance88 18:44905b008f44 47 DigitalOut dir_motor1(D7); //Direction motor 1
Vigilance88 18:44905b008f44 48 DigitalOut dir_motor2(D4); //Direction motor 2
Vigilance88 18:44905b008f44 49
Vigilance88 24:56db31267f10 50 //Limit Switches
Vigilance88 24:56db31267f10 51 DigitalIn shoulder_limit(PTA4); //using FRDM buttons for now
Vigilance88 24:56db31267f10 52 DigitalIn elbow_limit(PTC6); //using FRDM buttons for now
Vigilance88 24:56db31267f10 53
Vigilance88 21:d6a46315d5f5 54
Vigilance88 21:d6a46315d5f5 55 /*--------------------------------------------------------------------------------------------------------------------
Vigilance88 21:d6a46315d5f5 56 ---- DECLARE VARIABLES -----------------------------------------------------------------------------------------------
Vigilance88 21:d6a46315d5f5 57 --------------------------------------------------------------------------------------------------------------------*/
Vigilance88 21:d6a46315d5f5 58
Vigilance88 21:d6a46315d5f5 59 //EMG variables
Vigilance88 24:56db31267f10 60 double emg_biceps; double biceps_power; double bicepsMVC = 0;
Vigilance88 24:56db31267f10 61 double emg_triceps; double triceps_power; double tricepsMVC = 0;
Vigilance88 24:56db31267f10 62 double emg_flexor; double flexor_power; double flexorMVC = 0;
Vigilance88 24:56db31267f10 63 double emg_extens; double extens_power; double extensMVC = 0;
Vigilance88 24:56db31267f10 64
Vigilance88 24:56db31267f10 65 //PID variables
Vigilance88 24:56db31267f10 66 double u1; double u2; //Output of PID controller (PWM value for motor 1 and 2)
Vigilance88 24:56db31267f10 67 double m1_error=0; double m1_e_int=0; double m1_e_prev=0; //Error, integrated error, previous error
Vigilance88 24:56db31267f10 68 const double m1_kp=0; const double m1_ki=0; const double m1_kd=0; //Proportional, integral and derivative gains.
Vigilance88 24:56db31267f10 69
Vigilance88 24:56db31267f10 70 double m2_error=0; double m2_e_int=0; double m2_e_prev=0; //Error, integrated error, previous error
Vigilance88 24:56db31267f10 71 const double m2_kp=0; const double m2_ki=0; const double m2_kd=0; //Proportional, integral and derivative gains.
Vigilance88 24:56db31267f10 72
Vigilance88 24:56db31267f10 73 //highpass filter 20 Hz
Vigilance88 24:56db31267f10 74 const double high_b0 = 0.956543225556877;
Vigilance88 24:56db31267f10 75 const double high_b1 = -1.91308645113754;
Vigilance88 24:56db31267f10 76 const double high_b2 = 0.956543225556877;
Vigilance88 24:56db31267f10 77 const double high_a1 = -1.91197067426073;
Vigilance88 24:56db31267f10 78 const double high_a2 = 0.9149758348014341;
Vigilance88 24:56db31267f10 79
Vigilance88 24:56db31267f10 80 //notchfilter 50Hz
Vigilance88 24:56db31267f10 81 /* ** Primary Filter (H1)**
Vigilance88 24:56db31267f10 82 Filter Arithmetic = Floating Point (Double Precision)
Vigilance88 24:56db31267f10 83 Architecture = IIR
Vigilance88 24:56db31267f10 84 Response = Bandstop
Vigilance88 24:56db31267f10 85 Method = Butterworth
Vigilance88 24:56db31267f10 86 Biquad = Yes
Vigilance88 24:56db31267f10 87 Stable = Yes
Vigilance88 24:56db31267f10 88 Sampling Frequency = 500Hz
Vigilance88 24:56db31267f10 89 Filter Order = 2
Vigilance88 24:56db31267f10 90
Vigilance88 24:56db31267f10 91 Band Frequencies (Hz) Att/Ripple (dB) Biquad #1 Biquad #2
Vigilance88 24:56db31267f10 92
Vigilance88 24:56db31267f10 93 1 0, 48 0.001 Gain = 1.000000 Gain = 0.973674
Vigilance88 24:56db31267f10 94 2 49, 51 -60.000 B = [ 1.00000000000, -1.61816176147, 1.00000000000] B = [ 1.00000000000, -1.61816176147, 1.00000000000]
Vigilance88 24:56db31267f10 95 3 52, 250 0.001 A = [ 1.00000000000, -1.58071559235, 0.97319685401] A = [ 1.00000000000, -1.61244708381, 0.97415116257]
Vigilance88 24:56db31267f10 96 */
Vigilance88 24:56db31267f10 97
Vigilance88 24:56db31267f10 98 //biquad 1
Vigilance88 24:56db31267f10 99 const double notch1gain = 1.000000;
Vigilance88 24:56db31267f10 100 const double notch1_b0 = 1;
Vigilance88 24:56db31267f10 101 const double notch1_b1 = -1.61816176147 * notch1gain;
Vigilance88 24:56db31267f10 102 const double notch1_b2 = 1.00000000000 * notch1gain;
Vigilance88 24:56db31267f10 103 const double notch1_a1 = -1.58071559235 * notch1gain;
Vigilance88 24:56db31267f10 104 const double notch1_a2 = 0.97319685401 * notch1gain;
Vigilance88 24:56db31267f10 105
Vigilance88 24:56db31267f10 106 //biquad 2
Vigilance88 24:56db31267f10 107 const double notch2gain = 0.973674;
Vigilance88 24:56db31267f10 108 const double notch2_b0 = 1 * notch2gain;
Vigilance88 24:56db31267f10 109 const double notch2_b1 = -1.61816176147 * notch2gain;
Vigilance88 24:56db31267f10 110 const double notch2_b2 = 1.00000000000 * notch2gain;
Vigilance88 24:56db31267f10 111 const double notch2_a1 = -1.61244708381 * notch2gain;
Vigilance88 24:56db31267f10 112 const double notch2_a2 = 0.97415116257 * notch2gain;
Vigilance88 24:56db31267f10 113
Vigilance88 24:56db31267f10 114 //lowpass filter 7 Hz - envelop
Vigilance88 24:56db31267f10 115 const double low_b0 = 0.000119046743110057;
Vigilance88 24:56db31267f10 116 const double low_b1 = 0.000238093486220118;
Vigilance88 24:56db31267f10 117 const double low_b2 = 0.000119046743110057;
Vigilance88 24:56db31267f10 118 const double low_a1 = -1.968902268531908;
Vigilance88 24:56db31267f10 119 const double low_a2 = 0.9693784555043481;
Vigilance88 21:d6a46315d5f5 120
Vigilance88 21:d6a46315d5f5 121
Vigilance88 21:d6a46315d5f5 122
Vigilance88 21:d6a46315d5f5 123 /*--------------------------------------------------------------------------------------------------------------------
Vigilance88 24:56db31267f10 124 ---- Filters ---------------------------------------------------------------------------------------------------------
Vigilance88 21:d6a46315d5f5 125 --------------------------------------------------------------------------------------------------------------------*/
Vigilance88 24:56db31267f10 126
Vigilance88 24:56db31267f10 127 //Using biquadFilter library
Vigilance88 24:56db31267f10 128 //Syntax: biquadFilter filter(a1, a2, b0, b1, b2); coefficients. Call with: filter.step(u), with u signal to be filtered.
Vigilance88 24:56db31267f10 129 biquadFilter highpass( high_a1 , high_a2 , high_b0 , high_b1 , high_b2 ); // removes DC and movement artefacts
Vigilance88 24:56db31267f10 130 biquadFilter notch1( notch1_a1 , notch1_a2 , notch1_b0 , notch1_b1 , notch1_b2 ); // removes 49-51 Hz power interference
Vigilance88 24:56db31267f10 131 biquadFilter notch2( notch2_a1 , notch2_a2 , notch2_b0 , notch2_b1 , notch2_b2 ); //
Vigilance88 24:56db31267f10 132 biquadFilter lowpass( low_a1 , low_a2 , low_b0 , low_b1 , low_b2 ); // EMG envelope
Vigilance88 24:56db31267f10 133 biquadFilter derfilter( 0.0009446914586925257 , 0.0018893829173850514 , 0.0009446914586925257 , -1.911196288237583 , 0.914975054072353 ); // derivative filter
Vigilance88 24:56db31267f10 134
Vigilance88 24:56db31267f10 135 /*--------------------------------------------------------------------------------------------------------------------
Vigilance88 24:56db31267f10 136 ---- DECLARE FUNCTION NAMES ------------------------------------------------------------------------------------------
Vigilance88 24:56db31267f10 137 --------------------------------------------------------------------------------------------------------------------*/
Vigilance88 24:56db31267f10 138 void keep_in_range(double * in, double min, double max);
Vigilance88 21:d6a46315d5f5 139 void sample_filter(void);
Vigilance88 21:d6a46315d5f5 140 void control();
Vigilance88 21:d6a46315d5f5 141 void calibrate_emg(int muscle);
Vigilance88 21:d6a46315d5f5 142 void calibrate_arm(void);
Vigilance88 21:d6a46315d5f5 143 void start_sampling(void);
Vigilance88 21:d6a46315d5f5 144 void stop_sampling(void);
Vigilance88 21:d6a46315d5f5 145 void start_control(void);
Vigilance88 21:d6a46315d5f5 146 void stop_control(void);
Vigilance88 21:d6a46315d5f5 147 double pid(double error, double kp, double ki, double kd,double &e_int, double &e_prev);
Vigilance88 18:44905b008f44 148
Vigilance88 21:d6a46315d5f5 149 void mainMenu();
Vigilance88 21:d6a46315d5f5 150 void caliMenu();
Vigilance88 21:d6a46315d5f5 151
Vigilance88 21:d6a46315d5f5 152 /*--------------------------------------------------------------------------------------------------------------------
Vigilance88 21:d6a46315d5f5 153 ---- MAIN LOOP -------------------------------------------------------------------------------------------------------
Vigilance88 21:d6a46315d5f5 154 --------------------------------------------------------------------------------------------------------------------*/
Vigilance88 21:d6a46315d5f5 155
Vigilance88 21:d6a46315d5f5 156 int main()
Vigilance88 21:d6a46315d5f5 157 {
Vigilance88 24:56db31267f10 158 pc.baud(115200);
Vigilance88 24:56db31267f10 159 // make a menu, user has to initiate next step
Vigilance88 21:d6a46315d5f5 160 mainMenu();
Vigilance88 21:d6a46315d5f5 161 caliMenu(); // Menu function
Vigilance88 21:d6a46315d5f5 162 calibrate_arm(); //Start Calibration
Vigilance88 21:d6a46315d5f5 163 start_sampling(); //500 Hz EMG
Vigilance88 24:56db31267f10 164 calibrate_emg(1); //calibrate muscle 1
Vigilance88 21:d6a46315d5f5 165 start_control(); //100 Hz control
Vigilance88 21:d6a46315d5f5 166
Vigilance88 21:d6a46315d5f5 167 //maybe some stop commands when a button is pressed: detach from timers.
Vigilance88 21:d6a46315d5f5 168 //stop_control();
Vigilance88 21:d6a46315d5f5 169 //stop_sampling();
Vigilance88 21:d6a46315d5f5 170
Vigilance88 21:d6a46315d5f5 171 while(1) {
Vigilance88 21:d6a46315d5f5 172 scope.set(0,emg_biceps);
Vigilance88 21:d6a46315d5f5 173 scope.set(1,emg_triceps);
Vigilance88 21:d6a46315d5f5 174 scope.set(2,emg_flexor);
Vigilance88 21:d6a46315d5f5 175 scope.set(3,emg_extens);
Vigilance88 21:d6a46315d5f5 176 scope.send();
Vigilance88 21:d6a46315d5f5 177 }
Vigilance88 21:d6a46315d5f5 178 //end of while loop
Vigilance88 21:d6a46315d5f5 179 }
Vigilance88 21:d6a46315d5f5 180 //end of main
Vigilance88 21:d6a46315d5f5 181
Vigilance88 21:d6a46315d5f5 182 /*--------------------------------------------------------------------------------------------------------------------
Vigilance88 21:d6a46315d5f5 183 ---- FUNCTIONS -------------------------------------------------------------------------------------------------------
Vigilance88 21:d6a46315d5f5 184 --------------------------------------------------------------------------------------------------------------------*/
Vigilance88 18:44905b008f44 185
Vigilance88 21:d6a46315d5f5 186 //Sample and Filter
Vigilance88 21:d6a46315d5f5 187 void sample_filter(void)
Vigilance88 18:44905b008f44 188 {
Vigilance88 21:d6a46315d5f5 189 double emg_biceps = emg1.read(); //Biceps
Vigilance88 21:d6a46315d5f5 190 double emg_triceps = emg2.read(); //Triceps
Vigilance88 21:d6a46315d5f5 191 double emg_flexor = emg3.read(); //Flexor
Vigilance88 21:d6a46315d5f5 192 double emg_extens = emg4.read(); //Extensor
Vigilance88 21:d6a46315d5f5 193
Vigilance88 21:d6a46315d5f5 194 //Filter: high-pass -> notch -> rectify -> lowpass or moving average
Vigilance88 22:1ba637601dc3 195 // Can we use same biquadFilter (eg. highpass) for other muscles or does each muscle need its own biquad?
Vigilance88 21:d6a46315d5f5 196 biceps_power = highpass.step(emg_biceps); triceps_power = highpass.step(emg_triceps); flexor_power = highpass.step(emg_flexor); extens_power = highpass.step(emg_extens);
Vigilance88 21:d6a46315d5f5 197 biceps_power = notch1.step(biceps_power); triceps_power = notch1.step(triceps_power); flexor_power = notch1.step(flexor_power); extens_power = notch1.step(extens_power);
Vigilance88 21:d6a46315d5f5 198 biceps_power = notch2.step(biceps_power); triceps_power = notch2.step(triceps_power); flexor_power = notch2.step(flexor_power); extens_power = notch2.step(extens_power);
Vigilance88 21:d6a46315d5f5 199 biceps_power = abs(biceps_power); triceps_power = abs(triceps_power); flexor_power = abs(flexor_power); extens_power = abs(extens_power);
Vigilance88 21:d6a46315d5f5 200 biceps_power = lowpass.step(biceps_power); triceps_power = lowpass.step(triceps_power); flexor_power = lowpass.step(flexor_power); extens_power = lowpass.step(extens_power);
Vigilance88 21:d6a46315d5f5 201
Vigilance88 21:d6a46315d5f5 202 /* alternative for lowpass filter: moving average
Vigilance88 21:d6a46315d5f5 203 window=30; //30 samples
Vigilance88 21:d6a46315d5f5 204 int i=0; //buffer index
Vigilance88 21:d6a46315d5f5 205 bicepsbuffer[i]=biceps_power //fill array
Vigilance88 21:d6a46315d5f5 206
Vigilance88 21:d6a46315d5f5 207 i++;
Vigilance88 21:d6a46315d5f5 208 if(i==window){
Vigilance88 21:d6a46315d5f5 209 i=0;
Vigilance88 21:d6a46315d5f5 210 }
Vigilance88 21:d6a46315d5f5 211
Vigilance88 24:56db31267f10 212 for(int x = 0; x < window; x++){
Vigilance88 24:56db31267f10 213 avg1 += bicepsbuffer[x];
Vigilance88 24:56db31267f10 214 }
Vigilance88 24:56db31267f10 215 avg1 = avg1/window;
Vigilance88 21:d6a46315d5f5 216 */
Vigilance88 21:d6a46315d5f5 217
Vigilance88 18:44905b008f44 218 }
Vigilance88 18:44905b008f44 219
Vigilance88 18:44905b008f44 220 //Send arm to mechanical limits, and set encoder to 0. Then send arm to starting position.
Vigilance88 19:0a3ee31dcdb4 221 void calibrate_arm(void)
Vigilance88 19:0a3ee31dcdb4 222 {
Vigilance88 24:56db31267f10 223 bool hit = true;
Vigilance88 22:1ba637601dc3 224 dir_motor1=1; //ccw
Vigilance88 22:1ba637601dc3 225 dir_motor2=1; //ccw
Vigilance88 24:56db31267f10 226 while(shoulder_limit != hit){
Vigilance88 22:1ba637601dc3 227 pwm_motor1.write(0.4);
Vigilance88 24:56db31267f10 228 }
Vigilance88 24:56db31267f10 229 Encoder1.reset();
Vigilance88 24:56db31267f10 230
Vigilance88 24:56db31267f10 231 while(elbow_limit != hit){
Vigilance88 22:1ba637601dc3 232 pwm_motor2.write(0.4);
Vigilance88 22:1ba637601dc3 233 }
Vigilance88 24:56db31267f10 234 Encoder2.reset();
Vigilance88 19:0a3ee31dcdb4 235 }
Vigilance88 19:0a3ee31dcdb4 236
Vigilance88 21:d6a46315d5f5 237 //EMG Maximum Voluntary Contraction measurement
Vigilance88 21:d6a46315d5f5 238 void calibrate_emg(int muscle)
Vigilance88 18:44905b008f44 239 {
Vigilance88 21:d6a46315d5f5 240 start_sampling();
Vigilance88 24:56db31267f10 241
Vigilance88 24:56db31267f10 242 //double sampletime=0;
Vigilance88 24:56db31267f10 243 //sampletime=+SAMPLE_RATE;
Vigilance88 24:56db31267f10 244 //
Vigilance88 24:56db31267f10 245 // if(sampletime<5)
Vigilance88 21:d6a46315d5f5 246
Vigilance88 21:d6a46315d5f5 247 for(int index=0; index<2500;index++){ //measure 5 seconds@500hz = 2500 samples
Vigilance88 24:56db31267f10 248 if(muscle==1){
Vigilance88 24:56db31267f10 249
Vigilance88 24:56db31267f10 250 if(biceps_power>bicepsMVC){
Vigilance88 21:d6a46315d5f5 251 bicepsMVC=biceps_power;
Vigilance88 24:56db31267f10 252 }
Vigilance88 24:56db31267f10 253 }
Vigilance88 24:56db31267f10 254
Vigilance88 24:56db31267f10 255 if(muscle==2){
Vigilance88 24:56db31267f10 256
Vigilance88 24:56db31267f10 257 if(triceps_power>tricepsMVC){
Vigilance88 24:56db31267f10 258 tricepsMVC=triceps_power;
Vigilance88 24:56db31267f10 259 }
Vigilance88 24:56db31267f10 260 }
Vigilance88 24:56db31267f10 261
Vigilance88 24:56db31267f10 262 if(muscle==3){
Vigilance88 24:56db31267f10 263
Vigilance88 24:56db31267f10 264 if(flexor_power>flexorMVC){
Vigilance88 24:56db31267f10 265 flexorMVC=flexor_power;
Vigilance88 24:56db31267f10 266 }
Vigilance88 24:56db31267f10 267 }
Vigilance88 24:56db31267f10 268
Vigilance88 24:56db31267f10 269 if(muscle==4){
Vigilance88 24:56db31267f10 270
Vigilance88 24:56db31267f10 271 if(extens_power>extensMVC){
Vigilance88 24:56db31267f10 272 extensMVC=extens_power;
Vigilance88 24:56db31267f10 273 }
Vigilance88 24:56db31267f10 274 }
Vigilance88 21:d6a46315d5f5 275 }
Vigilance88 21:d6a46315d5f5 276 stop_sampling();
Vigilance88 24:56db31267f10 277
Vigilance88 18:44905b008f44 278 }
Vigilance88 18:44905b008f44 279
Vigilance88 18:44905b008f44 280
Vigilance88 18:44905b008f44 281 //Input error and Kp, Kd, Ki, output control signal
Vigilance88 20:0ede3818e08e 282 double pid(double error, double kp, double ki, double kd,double &e_int, double &e_prev)
vsluiter 2:e314bb3b2d99 283 {
Vigilance88 20:0ede3818e08e 284 // Derivative
Vigilance88 24:56db31267f10 285 double e_der = (error-e_prev)/ CONTROL_RATE;
Vigilance88 21:d6a46315d5f5 286 e_der = derfilter.step(e_der);
Vigilance88 21:d6a46315d5f5 287 e_prev = error;
Vigilance88 20:0ede3818e08e 288 // Integral
Vigilance88 24:56db31267f10 289 e_int = e_int + CONTROL_RATE * error;
Vigilance88 20:0ede3818e08e 290 // PID
Vigilance88 21:d6a46315d5f5 291 return kp*error + ki*e_int + kd * e_der;
Vigilance88 20:0ede3818e08e 292
Vigilance88 18:44905b008f44 293 }
Vigilance88 18:44905b008f44 294
Vigilance88 20:0ede3818e08e 295 //Analyze filtered EMG, calculate reference position from EMG, compare reference position with current position,convert to angles, send error through pid(), send PWM and DIR to motors
Vigilance88 18:44905b008f44 296 void control()
Vigilance88 18:44905b008f44 297 {
Vigilance88 20:0ede3818e08e 298 //analyze emg (= velocity, averages?)
Vigilance88 18:44905b008f44 299
Vigilance88 18:44905b008f44 300 //calculate reference position based on the average emg (integrate)
Vigilance88 18:44905b008f44 301
Vigilance88 18:44905b008f44 302 //calculate error (refpos-currentpos) currentpos = forward kinematics
Vigilance88 18:44905b008f44 303
Vigilance88 18:44905b008f44 304 //inverse kinematics (pos error to angle error)
Vigilance88 18:44905b008f44 305
Vigilance88 18:44905b008f44 306 //PID controller
Vigilance88 24:56db31267f10 307
Vigilance88 24:56db31267f10 308 u1=pid(m1_error,m1_kp,m1_ki,m1_kd,m1_e_int,m1_e_prev); //motor 1
Vigilance88 24:56db31267f10 309 u2=pid(m2_error,m2_kp,m2_ki,m2_kd,m2_e_int,m2_e_prev); //motor 2
Vigilance88 21:d6a46315d5f5 310
Vigilance88 21:d6a46315d5f5 311 keep_in_range(&u1,-1,1); //keep u between -1 and 1, sign = direction, PWM = 0-1
Vigilance88 21:d6a46315d5f5 312 keep_in_range(&u2,-1,1);
Vigilance88 21:d6a46315d5f5 313
Vigilance88 21:d6a46315d5f5 314 //send PWM and DIR to motor 1
Vigilance88 21:d6a46315d5f5 315 dir_motor1 = u1>0 ? 1 : 0; //conditional statement dir_motor1 = [condition] ? [if met 1] : [else 0]], same as if else below.
Vigilance88 21:d6a46315d5f5 316 pwm_motor1.write(abs(u1));
Vigilance88 21:d6a46315d5f5 317
Vigilance88 21:d6a46315d5f5 318 //send PWM and DIR to motor 2
Vigilance88 21:d6a46315d5f5 319 dir_motor1 = u2>0 ? 1 : 0; //conditional statement, same as if else below
Vigilance88 21:d6a46315d5f5 320 pwm_motor1.write(abs(u2));
Vigilance88 21:d6a46315d5f5 321
Vigilance88 21:d6a46315d5f5 322 /*if(u1 > 0)
Vigilance88 21:d6a46315d5f5 323 {
Vigilance88 21:d6a46315d5f5 324 dir_motor1 = 0;
Vigilance88 21:d6a46315d5f5 325 else{
Vigilance88 21:d6a46315d5f5 326 dir_motor1 = 1;
Vigilance88 21:d6a46315d5f5 327 }
Vigilance88 21:d6a46315d5f5 328 }
Vigilance88 21:d6a46315d5f5 329 pwm_motor1.write(abs(u1));
Vigilance88 21:d6a46315d5f5 330
Vigilance88 21:d6a46315d5f5 331
Vigilance88 21:d6a46315d5f5 332 if(u2 > 0)
Vigilance88 21:d6a46315d5f5 333 {
Vigilance88 21:d6a46315d5f5 334 dir_motor1 = 1;
Vigilance88 21:d6a46315d5f5 335 else{
Vigilance88 21:d6a46315d5f5 336 dir_motor1 = 0;
Vigilance88 21:d6a46315d5f5 337 }
Vigilance88 21:d6a46315d5f5 338 }
Vigilance88 21:d6a46315d5f5 339 pwm_motor1.write(abs(u2));*/
Vigilance88 21:d6a46315d5f5 340
Vigilance88 18:44905b008f44 341 }
Vigilance88 18:44905b008f44 342
Vigilance88 24:56db31267f10 343 void mainMenu(){};
Vigilance88 24:56db31267f10 344 void caliMenu(){};
Vigilance88 24:56db31267f10 345
Vigilance88 24:56db31267f10 346 //Start sampling
Vigilance88 24:56db31267f10 347 void start_sampling(void)
Vigilance88 24:56db31267f10 348 {
Vigilance88 24:56db31267f10 349 sample_timer.attach(&sample_filter,SAMPLE_RATE); //500 Hz EMG
Vigilance88 24:56db31267f10 350 }
Vigilance88 24:56db31267f10 351
Vigilance88 24:56db31267f10 352 //stop sampling
Vigilance88 24:56db31267f10 353 void stop_sampling(void)
Vigilance88 24:56db31267f10 354 {
Vigilance88 24:56db31267f10 355 sample_timer.detach();
Vigilance88 24:56db31267f10 356 }
Vigilance88 24:56db31267f10 357
Vigilance88 18:44905b008f44 358 //Start control
Vigilance88 18:44905b008f44 359 void start_control(void)
Vigilance88 18:44905b008f44 360 {
Vigilance88 24:56db31267f10 361 control_timer.attach(&control,CONTROL_RATE); //100 Hz control
Vigilance88 18:44905b008f44 362 }
Vigilance88 18:44905b008f44 363
Vigilance88 18:44905b008f44 364 //stop control
Vigilance88 18:44905b008f44 365 void stop_control(void)
Vigilance88 18:44905b008f44 366 {
Vigilance88 18:44905b008f44 367 control_timer.detach();
vsluiter 2:e314bb3b2d99 368 }
vsluiter 0:32bb76391d89 369
Vigilance88 21:d6a46315d5f5 370
Vigilance88 21:d6a46315d5f5 371 void calibrate()
vsluiter 0:32bb76391d89 372 {
Vigilance88 21:d6a46315d5f5 373
Vigilance88 21:d6a46315d5f5 374 }
tomlankhorst 15:0da764eea774 375
Vigilance88 21:d6a46315d5f5 376
Vigilance88 21:d6a46315d5f5 377 //keeps input limited between min max
Vigilance88 24:56db31267f10 378 void keep_in_range(double * in, double min, double max)
Vigilance88 18:44905b008f44 379 {
Vigilance88 18:44905b008f44 380 *in > min ? *in < max? : *in = max: *in = min;
vsluiter 0:32bb76391d89 381 }