testcode pid

Dependencies:   HIDScope MODSERIAL QEI biquadFilter mbed

Fork of testPID by Martijn Kern

Committer:
Vigilance88
Date:
Sun Oct 18 13:13:07 2015 +0000
Revision:
26:fe3a5469dd6b
Parent:
25:49ccdc98639a
Child:
27:0cefe83f83d3
- added more comments for clarity; - changed calibrate_arm; - updated mainMenu and other visual stuff

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 26:fe3a5469dd6b 7 #include <string>
Vigilance88 21:d6a46315d5f5 8
Vigilance88 21:d6a46315d5f5 9 /*--------------------------------------------------------------------------------------------------------------------
Vigilance88 21:d6a46315d5f5 10 -------------------------------- BIOROBOTICS GROUP 14 ----------------------------------------------------------------
Vigilance88 21:d6a46315d5f5 11 --------------------------------------------------------------------------------------------------------------------*/
vsluiter 0:32bb76391d89 12
Vigilance88 18:44905b008f44 13 //Define important constants in memory
Vigilance88 21:d6a46315d5f5 14 #define PI 3.14159265
Vigilance88 18:44905b008f44 15 #define SAMPLE_RATE 0.002 //500 Hz EMG sample rate
Vigilance88 18:44905b008f44 16 #define CONTROL_RATE 0.01 //100 Hz Control rate
Vigilance88 21:d6a46315d5f5 17 #define ENCODER1_CPR 4200 //encoders have 64 (X4), 32 (X2) counts per revolution of motor shaft
Vigilance88 21:d6a46315d5f5 18 #define ENCODER2_CPR 4200 //gearbox 1:131.25 -> 4200 counts per revolution of the output shaft (X2),
Vigilance88 26:fe3a5469dd6b 19 #define PWM_PERIOD 0.0001 //10k Hz pwm motor frequency. Higher -> too hot, lower -> motor doesnt respond correctly
Vigilance88 21:d6a46315d5f5 20 /*--------------------------------------------------------------------------------------------------------------------
Vigilance88 21:d6a46315d5f5 21 ---- OBJECTS ---------------------------------------------------------------------------------------------------------
Vigilance88 21:d6a46315d5f5 22 --------------------------------------------------------------------------------------------------------------------*/
Vigilance88 21:d6a46315d5f5 23
Vigilance88 18:44905b008f44 24 MODSERIAL pc(USBTX,USBRX); //serial communication
Vigilance88 18:44905b008f44 25
Vigilance88 25:49ccdc98639a 26 //Debug legs
Vigilance88 25:49ccdc98639a 27 DigitalOut red(LED_RED);
Vigilance88 25:49ccdc98639a 28 DigitalOut green(LED_GREEN);
Vigilance88 25:49ccdc98639a 29 DigitalOut blue(LED_BLUE);
Vigilance88 25:49ccdc98639a 30
Vigilance88 21:d6a46315d5f5 31 //EMG shields
Vigilance88 18:44905b008f44 32 AnalogIn emg1(A0); //Analog input - Biceps EMG
Vigilance88 18:44905b008f44 33 AnalogIn emg2(A1); //Analog input - Triceps EMG
Vigilance88 18:44905b008f44 34 AnalogIn emg3(A2); //Analog input - Flexor EMG
Vigilance88 18:44905b008f44 35 AnalogIn emg4(A3); //Analog input - Extensor EMG
Vigilance88 18:44905b008f44 36
Vigilance88 18:44905b008f44 37 Ticker sample_timer; //Ticker for EMG sampling
Vigilance88 18:44905b008f44 38 Ticker control_timer; //Ticker for control loop
Vigilance88 18:44905b008f44 39 HIDScope scope(4); //Scope 4 channels
Vigilance88 18:44905b008f44 40
Vigilance88 18:44905b008f44 41 // AnalogIn potmeter(A4); //potmeters
Vigilance88 18:44905b008f44 42 // AnalogIn potmeter2(A5); //
Vigilance88 18:44905b008f44 43
Vigilance88 21:d6a46315d5f5 44 //Encoders
Vigilance88 18:44905b008f44 45 QEI Encoder1(D13,D12,NC,32); //channel A and B from encoder, counts = Encoder.getPulses();
Vigilance88 18:44905b008f44 46 QEI Encoder2(D10,D9,NC,32); //channel A and B from encoder,
Vigilance88 21:d6a46315d5f5 47
Vigilance88 21:d6a46315d5f5 48 //Speed and Direction of motors - D4 (dir) and D5(speed) = motor 2, D7(dir) and D6(speed) = motor 1
Vigilance88 21:d6a46315d5f5 49 PwmOut pwm_motor1(D6); //PWM motor 1
Vigilance88 21:d6a46315d5f5 50 PwmOut pwm_motor2(D5); //PWM motor 2
Vigilance88 26:fe3a5469dd6b 51
Vigilance88 18:44905b008f44 52 DigitalOut dir_motor1(D7); //Direction motor 1
Vigilance88 18:44905b008f44 53 DigitalOut dir_motor2(D4); //Direction motor 2
Vigilance88 18:44905b008f44 54
Vigilance88 24:56db31267f10 55 //Limit Switches
Vigilance88 26:fe3a5469dd6b 56 InterruptIn shoulder_limit(D3); //using FRDM buttons
Vigilance88 26:fe3a5469dd6b 57 InterruptIn elbow_limit(D4); //using FRDM buttons
Vigilance88 26:fe3a5469dd6b 58
Vigilance88 26:fe3a5469dd6b 59 //Other buttons
Vigilance88 26:fe3a5469dd6b 60 DigitalIn button1(PTA4); //using FRDM buttons
Vigilance88 26:fe3a5469dd6b 61 DigitalIn button2(PTC6); //using FRDM buttons
Vigilance88 26:fe3a5469dd6b 62
Vigilance88 26:fe3a5469dd6b 63 /*Text colors ASCII code: Set Attribute Mode <ESC>[{attr1};...;{attrn}m
Vigilance88 26:fe3a5469dd6b 64
Vigilance88 26:fe3a5469dd6b 65 \ 0 3 3 - ESC
Vigilance88 26:fe3a5469dd6b 66 [ 3 0 m - black
Vigilance88 26:fe3a5469dd6b 67 [ 3 1 m - red
Vigilance88 26:fe3a5469dd6b 68 [ 3 2 m - green
Vigilance88 26:fe3a5469dd6b 69 [ 3 3 m - yellow
Vigilance88 26:fe3a5469dd6b 70 [ 3 4 m - blue
Vigilance88 26:fe3a5469dd6b 71 [ 3 5 m - magenta
Vigilance88 26:fe3a5469dd6b 72 [ 3 6 m - cyan
Vigilance88 26:fe3a5469dd6b 73 [ 3 7 m - white
Vigilance88 26:fe3a5469dd6b 74 [ 0 m - reset attributes
Vigilance88 26:fe3a5469dd6b 75
Vigilance88 26:fe3a5469dd6b 76 Put the text you want to color between GREEN_ and _GREEN
Vigilance88 26:fe3a5469dd6b 77 */
Vigilance88 26:fe3a5469dd6b 78 string GREEN_ = "\033[32m"; //esc - green
Vigilance88 26:fe3a5469dd6b 79 string _GREEN = "\033[0m"; //esc - reset
Vigilance88 24:56db31267f10 80
Vigilance88 21:d6a46315d5f5 81
Vigilance88 21:d6a46315d5f5 82 /*--------------------------------------------------------------------------------------------------------------------
Vigilance88 21:d6a46315d5f5 83 ---- DECLARE VARIABLES -----------------------------------------------------------------------------------------------
Vigilance88 21:d6a46315d5f5 84 --------------------------------------------------------------------------------------------------------------------*/
Vigilance88 21:d6a46315d5f5 85
Vigilance88 26:fe3a5469dd6b 86 //EMG variables: raw EMG - filtered EMG - maximum voluntary contraction
Vigilance88 24:56db31267f10 87 double emg_biceps; double biceps_power; double bicepsMVC = 0;
Vigilance88 24:56db31267f10 88 double emg_triceps; double triceps_power; double tricepsMVC = 0;
Vigilance88 24:56db31267f10 89 double emg_flexor; double flexor_power; double flexorMVC = 0;
Vigilance88 24:56db31267f10 90 double emg_extens; double extens_power; double extensMVC = 0;
Vigilance88 24:56db31267f10 91
Vigilance88 26:fe3a5469dd6b 92 int muscle; //Muscle selector for MVC measurement
Vigilance88 26:fe3a5469dd6b 93 double calibrate_time; //Elapsed time for each MVC measurement
Vigilance88 25:49ccdc98639a 94
Vigilance88 24:56db31267f10 95 //PID variables
Vigilance88 24:56db31267f10 96 double u1; double u2; //Output of PID controller (PWM value for motor 1 and 2)
Vigilance88 24:56db31267f10 97 double m1_error=0; double m1_e_int=0; double m1_e_prev=0; //Error, integrated error, previous error
Vigilance88 24:56db31267f10 98 const double m1_kp=0; const double m1_ki=0; const double m1_kd=0; //Proportional, integral and derivative gains.
Vigilance88 24:56db31267f10 99
Vigilance88 26:fe3a5469dd6b 100 double m2_error=0; double m2_e_int=0; double m2_e_prev=0; //Error, integrated error, previous error
Vigilance88 24:56db31267f10 101 const double m2_kp=0; const double m2_ki=0; const double m2_kd=0; //Proportional, integral and derivative gains.
Vigilance88 24:56db31267f10 102
Vigilance88 24:56db31267f10 103 //highpass filter 20 Hz
Vigilance88 24:56db31267f10 104 const double high_b0 = 0.956543225556877;
Vigilance88 24:56db31267f10 105 const double high_b1 = -1.91308645113754;
Vigilance88 24:56db31267f10 106 const double high_b2 = 0.956543225556877;
Vigilance88 24:56db31267f10 107 const double high_a1 = -1.91197067426073;
Vigilance88 24:56db31267f10 108 const double high_a2 = 0.9149758348014341;
Vigilance88 24:56db31267f10 109
Vigilance88 24:56db31267f10 110 //notchfilter 50Hz
Vigilance88 24:56db31267f10 111 /* ** Primary Filter (H1)**
Vigilance88 24:56db31267f10 112 Filter Arithmetic = Floating Point (Double Precision)
Vigilance88 24:56db31267f10 113 Architecture = IIR
Vigilance88 24:56db31267f10 114 Response = Bandstop
Vigilance88 24:56db31267f10 115 Method = Butterworth
Vigilance88 24:56db31267f10 116 Biquad = Yes
Vigilance88 24:56db31267f10 117 Stable = Yes
Vigilance88 24:56db31267f10 118 Sampling Frequency = 500Hz
Vigilance88 24:56db31267f10 119 Filter Order = 2
Vigilance88 24:56db31267f10 120
Vigilance88 24:56db31267f10 121 Band Frequencies (Hz) Att/Ripple (dB) Biquad #1 Biquad #2
Vigilance88 24:56db31267f10 122
Vigilance88 24:56db31267f10 123 1 0, 48 0.001 Gain = 1.000000 Gain = 0.973674
Vigilance88 24:56db31267f10 124 2 49, 51 -60.000 B = [ 1.00000000000, -1.61816176147, 1.00000000000] B = [ 1.00000000000, -1.61816176147, 1.00000000000]
Vigilance88 24:56db31267f10 125 3 52, 250 0.001 A = [ 1.00000000000, -1.58071559235, 0.97319685401] A = [ 1.00000000000, -1.61244708381, 0.97415116257]
Vigilance88 24:56db31267f10 126 */
Vigilance88 24:56db31267f10 127
Vigilance88 24:56db31267f10 128 //biquad 1
Vigilance88 24:56db31267f10 129 const double notch1gain = 1.000000;
Vigilance88 24:56db31267f10 130 const double notch1_b0 = 1;
Vigilance88 24:56db31267f10 131 const double notch1_b1 = -1.61816176147 * notch1gain;
Vigilance88 24:56db31267f10 132 const double notch1_b2 = 1.00000000000 * notch1gain;
Vigilance88 24:56db31267f10 133 const double notch1_a1 = -1.58071559235 * notch1gain;
Vigilance88 24:56db31267f10 134 const double notch1_a2 = 0.97319685401 * notch1gain;
Vigilance88 24:56db31267f10 135
Vigilance88 24:56db31267f10 136 //biquad 2
Vigilance88 24:56db31267f10 137 const double notch2gain = 0.973674;
Vigilance88 24:56db31267f10 138 const double notch2_b0 = 1 * notch2gain;
Vigilance88 24:56db31267f10 139 const double notch2_b1 = -1.61816176147 * notch2gain;
Vigilance88 24:56db31267f10 140 const double notch2_b2 = 1.00000000000 * notch2gain;
Vigilance88 24:56db31267f10 141 const double notch2_a1 = -1.61244708381 * notch2gain;
Vigilance88 24:56db31267f10 142 const double notch2_a2 = 0.97415116257 * notch2gain;
Vigilance88 24:56db31267f10 143
Vigilance88 26:fe3a5469dd6b 144 //lowpass filter 7 Hz - envelope
Vigilance88 24:56db31267f10 145 const double low_b0 = 0.000119046743110057;
Vigilance88 24:56db31267f10 146 const double low_b1 = 0.000238093486220118;
Vigilance88 24:56db31267f10 147 const double low_b2 = 0.000119046743110057;
Vigilance88 24:56db31267f10 148 const double low_a1 = -1.968902268531908;
Vigilance88 24:56db31267f10 149 const double low_a2 = 0.9693784555043481;
Vigilance88 21:d6a46315d5f5 150
Vigilance88 21:d6a46315d5f5 151
Vigilance88 21:d6a46315d5f5 152 /*--------------------------------------------------------------------------------------------------------------------
Vigilance88 24:56db31267f10 153 ---- Filters ---------------------------------------------------------------------------------------------------------
Vigilance88 21:d6a46315d5f5 154 --------------------------------------------------------------------------------------------------------------------*/
Vigilance88 24:56db31267f10 155
Vigilance88 24:56db31267f10 156 //Using biquadFilter library
Vigilance88 24:56db31267f10 157 //Syntax: biquadFilter filter(a1, a2, b0, b1, b2); coefficients. Call with: filter.step(u), with u signal to be filtered.
Vigilance88 26:fe3a5469dd6b 158 //Biceps
Vigilance88 24:56db31267f10 159 biquadFilter highpass( high_a1 , high_a2 , high_b0 , high_b1 , high_b2 ); // removes DC and movement artefacts
Vigilance88 24:56db31267f10 160 biquadFilter notch1( notch1_a1 , notch1_a2 , notch1_b0 , notch1_b1 , notch1_b2 ); // removes 49-51 Hz power interference
Vigilance88 24:56db31267f10 161 biquadFilter notch2( notch2_a1 , notch2_a2 , notch2_b0 , notch2_b1 , notch2_b2 ); //
Vigilance88 24:56db31267f10 162 biquadFilter lowpass( low_a1 , low_a2 , low_b0 , low_b1 , low_b2 ); // EMG envelope
Vigilance88 25:49ccdc98639a 163
Vigilance88 26:fe3a5469dd6b 164 //Triceps
Vigilance88 25:49ccdc98639a 165 biquadFilter highpass2( high_a1 , high_a2 , high_b0 , high_b1 , high_b2 ); // removes DC and movement artefacts
Vigilance88 26:fe3a5469dd6b 166 biquadFilter notch1_2( notch1_a1 , notch1_a2 , notch1_b0 , notch1_b1 , notch1_b2 ); // removes 49-51 Hz power interference
Vigilance88 26:fe3a5469dd6b 167 biquadFilter notch2_2( notch2_a1 , notch2_a2 , notch2_b0 , notch2_b1 , notch2_b2 ); //
Vigilance88 25:49ccdc98639a 168 biquadFilter lowpass2( low_a1 , low_a2 , low_b0 , low_b1 , low_b2 ); // EMG envelope
Vigilance88 25:49ccdc98639a 169
Vigilance88 26:fe3a5469dd6b 170 //Flexor
Vigilance88 25:49ccdc98639a 171 biquadFilter highpass3( high_a1 , high_a2 , high_b0 , high_b1 , high_b2 ); // removes DC and movement artefacts
Vigilance88 26:fe3a5469dd6b 172 biquadFilter notch1_3( notch1_a1 , notch1_a2 , notch1_b0 , notch1_b1 , notch1_b2 ); // removes 49-51 Hz power interference
Vigilance88 26:fe3a5469dd6b 173 biquadFilter notch2_3( notch2_a1 , notch2_a2 , notch2_b0 , notch2_b1 , notch2_b2 ); //
Vigilance88 25:49ccdc98639a 174 biquadFilter lowpass3( low_a1 , low_a2 , low_b0 , low_b1 , low_b2 ); // EMG envelope
Vigilance88 25:49ccdc98639a 175
Vigilance88 26:fe3a5469dd6b 176 //Extensor
Vigilance88 25:49ccdc98639a 177 biquadFilter highpass4( high_a1 , high_a2 , high_b0 , high_b1 , high_b2 ); // removes DC and movement artefacts
Vigilance88 26:fe3a5469dd6b 178 biquadFilter notch1_4( notch1_a1 , notch1_a2 , notch1_b0 , notch1_b1 , notch1_b2 ); // removes 49-51 Hz power interference
Vigilance88 26:fe3a5469dd6b 179 biquadFilter notch2_4( notch2_a1 , notch2_a2 , notch2_b0 , notch2_b1 , notch2_b2 ); //
Vigilance88 25:49ccdc98639a 180 biquadFilter lowpass4( low_a1 , low_a2 , low_b0 , low_b1 , low_b2 ); // EMG envelope
Vigilance88 25:49ccdc98639a 181
Vigilance88 26:fe3a5469dd6b 182 //PID filter (lowpass ??? Hz)
Vigilance88 24:56db31267f10 183 biquadFilter derfilter( 0.0009446914586925257 , 0.0018893829173850514 , 0.0009446914586925257 , -1.911196288237583 , 0.914975054072353 ); // derivative filter
Vigilance88 24:56db31267f10 184
Vigilance88 24:56db31267f10 185 /*--------------------------------------------------------------------------------------------------------------------
Vigilance88 24:56db31267f10 186 ---- DECLARE FUNCTION NAMES ------------------------------------------------------------------------------------------
Vigilance88 24:56db31267f10 187 --------------------------------------------------------------------------------------------------------------------*/
Vigilance88 26:fe3a5469dd6b 188
Vigilance88 26:fe3a5469dd6b 189 void sample_filter(void); //Sampling and filtering
Vigilance88 26:fe3a5469dd6b 190 void control(); //Control - reference -> error -> pid -> motor output
Vigilance88 26:fe3a5469dd6b 191 void calibrate_emg(); //Instructions + measurement of MVC of each muscle
Vigilance88 26:fe3a5469dd6b 192 void emg_mvc(); //Helper funcion for storing MVC value
Vigilance88 26:fe3a5469dd6b 193 void calibrate_arm(void); //Calibration of the arm with limit switches
Vigilance88 26:fe3a5469dd6b 194 void start_sampling(void); //Attaches the sample_filter function to a 500Hz ticker
Vigilance88 26:fe3a5469dd6b 195 void stop_sampling(void); //Stops sample_filter
Vigilance88 26:fe3a5469dd6b 196 void start_control(void); //Attaches the control function to a 100Hz ticker
Vigilance88 26:fe3a5469dd6b 197 void stop_control(void); //Stops control function
Vigilance88 26:fe3a5469dd6b 198
Vigilance88 26:fe3a5469dd6b 199 //Keeps the input between min and max value
Vigilance88 24:56db31267f10 200 void keep_in_range(double * in, double min, double max);
Vigilance88 26:fe3a5469dd6b 201
Vigilance88 26:fe3a5469dd6b 202 //Reusable PID controller, previous and integral error need to be passed by reference
Vigilance88 21:d6a46315d5f5 203 double pid(double error, double kp, double ki, double kd,double &e_int, double &e_prev);
Vigilance88 18:44905b008f44 204
Vigilance88 26:fe3a5469dd6b 205 //Menu functions
Vigilance88 21:d6a46315d5f5 206 void mainMenu();
Vigilance88 21:d6a46315d5f5 207 void caliMenu();
Vigilance88 26:fe3a5469dd6b 208 void clearTerminal();
Vigilance88 26:fe3a5469dd6b 209
Vigilance88 21:d6a46315d5f5 210
Vigilance88 21:d6a46315d5f5 211 /*--------------------------------------------------------------------------------------------------------------------
Vigilance88 21:d6a46315d5f5 212 ---- MAIN LOOP -------------------------------------------------------------------------------------------------------
Vigilance88 21:d6a46315d5f5 213 --------------------------------------------------------------------------------------------------------------------*/
Vigilance88 21:d6a46315d5f5 214
Vigilance88 21:d6a46315d5f5 215 int main()
Vigilance88 21:d6a46315d5f5 216 {
Vigilance88 26:fe3a5469dd6b 217 pc.baud(115200); //terminal baudrate
Vigilance88 26:fe3a5469dd6b 218 red=1; green=1; blue=1; //Make sure debug LEDS are off
Vigilance88 26:fe3a5469dd6b 219
Vigilance88 26:fe3a5469dd6b 220 //Set PwmOut frequency to 10k Hz
Vigilance88 26:fe3a5469dd6b 221 pwm_motor1.period(PWM_PERIOD);
Vigilance88 26:fe3a5469dd6b 222 pwm_motor2.period(PWM_PERIOD);
Vigilance88 26:fe3a5469dd6b 223
Vigilance88 26:fe3a5469dd6b 224 clearTerminal(); //Clear the putty window
Vigilance88 26:fe3a5469dd6b 225
Vigilance88 24:56db31267f10 226 // make a menu, user has to initiate next step
Vigilance88 26:fe3a5469dd6b 227 mainMenu();
Vigilance88 25:49ccdc98639a 228 //caliMenu(); // Menu function
Vigilance88 25:49ccdc98639a 229 //calibrate_arm(); //Start Calibration
Vigilance88 25:49ccdc98639a 230
Vigilance88 25:49ccdc98639a 231 calibrate_emg();
Vigilance88 25:49ccdc98639a 232
Vigilance88 25:49ccdc98639a 233 //start_control(); //100 Hz control
Vigilance88 21:d6a46315d5f5 234
Vigilance88 21:d6a46315d5f5 235 //maybe some stop commands when a button is pressed: detach from timers.
Vigilance88 21:d6a46315d5f5 236 //stop_control();
Vigilance88 21:d6a46315d5f5 237 //stop_sampling();
Vigilance88 21:d6a46315d5f5 238
Vigilance88 21:d6a46315d5f5 239 while(1) {
Vigilance88 25:49ccdc98639a 240
Vigilance88 21:d6a46315d5f5 241 }
Vigilance88 21:d6a46315d5f5 242 //end of while loop
Vigilance88 21:d6a46315d5f5 243 }
Vigilance88 21:d6a46315d5f5 244 //end of main
Vigilance88 21:d6a46315d5f5 245
Vigilance88 21:d6a46315d5f5 246 /*--------------------------------------------------------------------------------------------------------------------
Vigilance88 21:d6a46315d5f5 247 ---- FUNCTIONS -------------------------------------------------------------------------------------------------------
Vigilance88 21:d6a46315d5f5 248 --------------------------------------------------------------------------------------------------------------------*/
Vigilance88 18:44905b008f44 249
Vigilance88 21:d6a46315d5f5 250 //Sample and Filter
Vigilance88 21:d6a46315d5f5 251 void sample_filter(void)
Vigilance88 18:44905b008f44 252 {
Vigilance88 21:d6a46315d5f5 253 double emg_biceps = emg1.read(); //Biceps
Vigilance88 21:d6a46315d5f5 254 double emg_triceps = emg2.read(); //Triceps
Vigilance88 21:d6a46315d5f5 255 double emg_flexor = emg3.read(); //Flexor
Vigilance88 21:d6a46315d5f5 256 double emg_extens = emg4.read(); //Extensor
Vigilance88 21:d6a46315d5f5 257
Vigilance88 21:d6a46315d5f5 258 //Filter: high-pass -> notch -> rectify -> lowpass or moving average
Vigilance88 22:1ba637601dc3 259 // Can we use same biquadFilter (eg. highpass) for other muscles or does each muscle need its own biquad?
Vigilance88 25:49ccdc98639a 260 biceps_power = highpass.step(emg_biceps); triceps_power = highpass2.step(emg_triceps); flexor_power = highpass3.step(emg_flexor); extens_power = highpass4.step(emg_extens);
Vigilance88 25:49ccdc98639a 261 biceps_power = notch1.step(biceps_power); triceps_power = notch1_2.step(triceps_power); flexor_power = notch1_3.step(flexor_power); extens_power = notch1_4.step(extens_power);
Vigilance88 25:49ccdc98639a 262 biceps_power = notch2.step(biceps_power); triceps_power = notch2_2.step(triceps_power); flexor_power = notch2_3.step(flexor_power); extens_power = notch2_4.step(extens_power);
Vigilance88 21:d6a46315d5f5 263 biceps_power = abs(biceps_power); triceps_power = abs(triceps_power); flexor_power = abs(flexor_power); extens_power = abs(extens_power);
Vigilance88 25:49ccdc98639a 264 biceps_power = lowpass.step(biceps_power); triceps_power = lowpass2.step(triceps_power); flexor_power = lowpass3.step(flexor_power); extens_power = lowpass4.step(extens_power);
Vigilance88 25:49ccdc98639a 265
Vigilance88 21:d6a46315d5f5 266
Vigilance88 21:d6a46315d5f5 267 /* alternative for lowpass filter: moving average
Vigilance88 21:d6a46315d5f5 268 window=30; //30 samples
Vigilance88 21:d6a46315d5f5 269 int i=0; //buffer index
Vigilance88 21:d6a46315d5f5 270 bicepsbuffer[i]=biceps_power //fill array
Vigilance88 21:d6a46315d5f5 271
Vigilance88 21:d6a46315d5f5 272 i++;
Vigilance88 21:d6a46315d5f5 273 if(i==window){
Vigilance88 21:d6a46315d5f5 274 i=0;
Vigilance88 21:d6a46315d5f5 275 }
Vigilance88 21:d6a46315d5f5 276
Vigilance88 24:56db31267f10 277 for(int x = 0; x < window; x++){
Vigilance88 24:56db31267f10 278 avg1 += bicepsbuffer[x];
Vigilance88 24:56db31267f10 279 }
Vigilance88 24:56db31267f10 280 avg1 = avg1/window;
Vigilance88 21:d6a46315d5f5 281 */
Vigilance88 21:d6a46315d5f5 282
Vigilance88 18:44905b008f44 283 }
Vigilance88 18:44905b008f44 284
Vigilance88 18:44905b008f44 285 //Send arm to mechanical limits, and set encoder to 0. Then send arm to starting position.
Vigilance88 19:0a3ee31dcdb4 286 void calibrate_arm(void)
Vigilance88 19:0a3ee31dcdb4 287 {
Vigilance88 26:fe3a5469dd6b 288 red=0; blue=0; //Debug light is purple during arm calibration
Vigilance88 26:fe3a5469dd6b 289 bool calibrating = true;
Vigilance88 26:fe3a5469dd6b 290 bool done1 = false;
Vigilance88 26:fe3a5469dd6b 291 bool done2 = false;
Vigilance88 26:fe3a5469dd6b 292 dir_motor1=1; //cw
Vigilance88 26:fe3a5469dd6b 293 dir_motor2=1; //cw
Vigilance88 26:fe3a5469dd6b 294 pwm_motor1.write(0.2f); //move upper arm slowly cw
Vigilance88 26:fe3a5469dd6b 295 pwm_motor2.write(0.2f); //move forearm slowly cw
Vigilance88 26:fe3a5469dd6b 296
Vigilance88 26:fe3a5469dd6b 297 while(calibrating){
Vigilance88 25:49ccdc98639a 298
Vigilance88 26:fe3a5469dd6b 299 //when limit switches are hit, stop motor and reset encoder
Vigilance88 26:fe3a5469dd6b 300 if(shoulder_limit.read() < 0.5){ //polling
Vigilance88 26:fe3a5469dd6b 301 pwm_motor1.write(0);
Vigilance88 26:fe3a5469dd6b 302 Encoder1.reset();
Vigilance88 26:fe3a5469dd6b 303 done1 = true;
Vigilance88 26:fe3a5469dd6b 304 }
Vigilance88 26:fe3a5469dd6b 305 if(elbow_limit.read() < 0.5){ //polling
Vigilance88 26:fe3a5469dd6b 306 pwm_motor2.write(0);
Vigilance88 26:fe3a5469dd6b 307 Encoder2.reset();
Vigilance88 26:fe3a5469dd6b 308 done2 = true;
Vigilance88 26:fe3a5469dd6b 309 }
Vigilance88 26:fe3a5469dd6b 310 if(done1 && done2){
Vigilance88 26:fe3a5469dd6b 311 calibrating=false; //Leave while loop when both limits are reached
Vigilance88 26:fe3a5469dd6b 312 red=1; blue=1; //Turn debug light off when calibration complete
Vigilance88 26:fe3a5469dd6b 313 }
Vigilance88 25:49ccdc98639a 314
Vigilance88 26:fe3a5469dd6b 315 }//end while
Vigilance88 26:fe3a5469dd6b 316
Vigilance88 19:0a3ee31dcdb4 317 }
Vigilance88 19:0a3ee31dcdb4 318
Vigilance88 21:d6a46315d5f5 319 //EMG Maximum Voluntary Contraction measurement
Vigilance88 25:49ccdc98639a 320 void emg_mvc()
Vigilance88 25:49ccdc98639a 321 {
Vigilance88 24:56db31267f10 322 //double sampletime=0;
Vigilance88 24:56db31267f10 323 //sampletime=+SAMPLE_RATE;
Vigilance88 24:56db31267f10 324 //
Vigilance88 24:56db31267f10 325 // if(sampletime<5)
Vigilance88 25:49ccdc98639a 326 //int muscle=1;
Vigilance88 25:49ccdc98639a 327 //for(int index=0; index<2500;index++){ //measure 5 seconds@500hz = 2500 samples
Vigilance88 25:49ccdc98639a 328
Vigilance88 24:56db31267f10 329 if(muscle==1){
Vigilance88 24:56db31267f10 330
Vigilance88 24:56db31267f10 331 if(biceps_power>bicepsMVC){
Vigilance88 26:fe3a5469dd6b 332 //printf("+ ");
Vigilance88 26:fe3a5469dd6b 333 printf("%s+ %s",GREEN_,_GREEN);
Vigilance88 21:d6a46315d5f5 334 bicepsMVC=biceps_power;
Vigilance88 24:56db31267f10 335 }
Vigilance88 25:49ccdc98639a 336 else
Vigilance88 25:49ccdc98639a 337 printf("- ");
Vigilance88 24:56db31267f10 338 }
Vigilance88 24:56db31267f10 339
Vigilance88 24:56db31267f10 340 if(muscle==2){
Vigilance88 24:56db31267f10 341
Vigilance88 24:56db31267f10 342 if(triceps_power>tricepsMVC){
Vigilance88 26:fe3a5469dd6b 343 printf("%s+ %s",GREEN_,_GREEN);
Vigilance88 24:56db31267f10 344 tricepsMVC=triceps_power;
Vigilance88 24:56db31267f10 345 }
Vigilance88 26:fe3a5469dd6b 346 else
Vigilance88 26:fe3a5469dd6b 347 printf("- ");
Vigilance88 24:56db31267f10 348 }
Vigilance88 24:56db31267f10 349
Vigilance88 24:56db31267f10 350 if(muscle==3){
Vigilance88 24:56db31267f10 351
Vigilance88 24:56db31267f10 352 if(flexor_power>flexorMVC){
Vigilance88 26:fe3a5469dd6b 353 printf("%s+ %s",GREEN_,_GREEN);
Vigilance88 24:56db31267f10 354 flexorMVC=flexor_power;
Vigilance88 24:56db31267f10 355 }
Vigilance88 26:fe3a5469dd6b 356 else
Vigilance88 26:fe3a5469dd6b 357 printf("- ");
Vigilance88 24:56db31267f10 358 }
Vigilance88 24:56db31267f10 359
Vigilance88 24:56db31267f10 360 if(muscle==4){
Vigilance88 24:56db31267f10 361
Vigilance88 24:56db31267f10 362 if(extens_power>extensMVC){
Vigilance88 26:fe3a5469dd6b 363 printf("%s+ %s",GREEN_,_GREEN);
Vigilance88 24:56db31267f10 364 extensMVC=extens_power;
Vigilance88 24:56db31267f10 365 }
Vigilance88 26:fe3a5469dd6b 366 else
Vigilance88 26:fe3a5469dd6b 367 printf("- ");
Vigilance88 24:56db31267f10 368 }
Vigilance88 25:49ccdc98639a 369
Vigilance88 25:49ccdc98639a 370 //}
Vigilance88 25:49ccdc98639a 371 calibrate_time = calibrate_time + 0.002;
Vigilance88 25:49ccdc98639a 372
Vigilance88 25:49ccdc98639a 373
Vigilance88 25:49ccdc98639a 374
Vigilance88 25:49ccdc98639a 375 }
Vigilance88 25:49ccdc98639a 376
Vigilance88 25:49ccdc98639a 377 //EMG calibration
Vigilance88 25:49ccdc98639a 378 void calibrate_emg()
Vigilance88 25:49ccdc98639a 379 {
Vigilance88 25:49ccdc98639a 380 Ticker timer;
Vigilance88 25:49ccdc98639a 381
Vigilance88 25:49ccdc98639a 382 pc.printf("Testcode calibration \r\n");
Vigilance88 25:49ccdc98639a 383 wait(1);
Vigilance88 25:49ccdc98639a 384 pc.printf("+ means current sample is higher than stored MVC\r\n");
Vigilance88 25:49ccdc98639a 385 pc.printf("- means current sample is lower than stored MVC\r\n");
Vigilance88 26:fe3a5469dd6b 386 wait(2);
Vigilance88 25:49ccdc98639a 387 pc.printf(" Biceps is first. "); wait(1);
Vigilance88 25:49ccdc98639a 388 pc.printf(" Press any key to begin... "); wait(1);
Vigilance88 25:49ccdc98639a 389 char input;
Vigilance88 25:49ccdc98639a 390 input=pc.getc();
Vigilance88 25:49ccdc98639a 391 pc.putc(input);
Vigilance88 25:49ccdc98639a 392 pc.printf(" \r\n Starting in 3... \r\n"); wait(1);
Vigilance88 25:49ccdc98639a 393 pc.printf(" \r\n Starting in 2... \r\n"); wait(1);
Vigilance88 25:49ccdc98639a 394 pc.printf(" \r\n Starting in 1... \r\n"); wait(1);
Vigilance88 25:49ccdc98639a 395
Vigilance88 25:49ccdc98639a 396 start_sampling();
Vigilance88 25:49ccdc98639a 397 muscle=1;
Vigilance88 25:49ccdc98639a 398 timer.attach(&emg_mvc,0.002);
Vigilance88 25:49ccdc98639a 399 wait(5);
Vigilance88 25:49ccdc98639a 400 timer.detach();
Vigilance88 26:fe3a5469dd6b 401
Vigilance88 26:fe3a5469dd6b 402 pc.printf("\r\n Measurement complete."); wait(1);
Vigilance88 26:fe3a5469dd6b 403 pc.printf("\r\n Biceps MVC = %f \r\n",bicepsMVC); wait(1);
Vigilance88 26:fe3a5469dd6b 404 pc.printf("Calibrate_emg() exited \r\n"); wait(1);
Vigilance88 26:fe3a5469dd6b 405 pc.printf("Measured time: %f seconds \r\n\n",calibrate_time);
Vigilance88 25:49ccdc98639a 406 calibrate_time=0;
Vigilance88 25:49ccdc98639a 407
Vigilance88 25:49ccdc98639a 408 // Triceps:
Vigilance88 26:fe3a5469dd6b 409 muscle=2;
Vigilance88 25:49ccdc98639a 410 pc.printf(" Triceps is next "); wait(1);
Vigilance88 25:49ccdc98639a 411 pc.printf(" Press any key to begin... "); wait(1);
Vigilance88 25:49ccdc98639a 412 input=pc.getc();
Vigilance88 25:49ccdc98639a 413 pc.putc(input);
Vigilance88 25:49ccdc98639a 414 pc.printf(" \r\n Starting in 3... \r\n"); wait(1);
Vigilance88 25:49ccdc98639a 415 pc.printf(" \r\n Starting in 2... \r\n"); wait(1);
Vigilance88 25:49ccdc98639a 416 pc.printf(" \r\n Starting in 1... \r\n"); wait(1);
Vigilance88 25:49ccdc98639a 417 start_sampling();
Vigilance88 25:49ccdc98639a 418 muscle=1;
Vigilance88 25:49ccdc98639a 419 timer.attach(&emg_mvc,0.002);
Vigilance88 25:49ccdc98639a 420 wait(5);
Vigilance88 25:49ccdc98639a 421 timer.detach();
Vigilance88 25:49ccdc98639a 422 pc.printf("\r\n Triceps MVC = %f \r\n",tricepsMVC);
Vigilance88 25:49ccdc98639a 423
Vigilance88 25:49ccdc98639a 424 pc.printf("Calibrate_emg() exited \r\n");
Vigilance88 25:49ccdc98639a 425 pc.printf("Measured time: %f seconds \r\n",calibrate_time);
Vigilance88 25:49ccdc98639a 426 calibrate_time=0;
Vigilance88 25:49ccdc98639a 427
Vigilance88 25:49ccdc98639a 428 //Flexor:
Vigilance88 26:fe3a5469dd6b 429 muscle=3;
Vigilance88 25:49ccdc98639a 430 //Extensor:
Vigilance88 26:fe3a5469dd6b 431 muscle=4;
Vigilance88 25:49ccdc98639a 432
Vigilance88 26:fe3a5469dd6b 433 //Stop sampling, detach ticker
Vigilance88 25:49ccdc98639a 434 stop_sampling();
Vigilance88 24:56db31267f10 435
Vigilance88 18:44905b008f44 436 }
Vigilance88 18:44905b008f44 437
Vigilance88 18:44905b008f44 438
Vigilance88 18:44905b008f44 439 //Input error and Kp, Kd, Ki, output control signal
Vigilance88 20:0ede3818e08e 440 double pid(double error, double kp, double ki, double kd,double &e_int, double &e_prev)
vsluiter 2:e314bb3b2d99 441 {
Vigilance88 20:0ede3818e08e 442 // Derivative
Vigilance88 24:56db31267f10 443 double e_der = (error-e_prev)/ CONTROL_RATE;
Vigilance88 21:d6a46315d5f5 444 e_der = derfilter.step(e_der);
Vigilance88 21:d6a46315d5f5 445 e_prev = error;
Vigilance88 20:0ede3818e08e 446 // Integral
Vigilance88 24:56db31267f10 447 e_int = e_int + CONTROL_RATE * error;
Vigilance88 20:0ede3818e08e 448 // PID
Vigilance88 21:d6a46315d5f5 449 return kp*error + ki*e_int + kd * e_der;
Vigilance88 20:0ede3818e08e 450
Vigilance88 18:44905b008f44 451 }
Vigilance88 18:44905b008f44 452
Vigilance88 20:0ede3818e08e 453 //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 454 void control()
Vigilance88 18:44905b008f44 455 {
Vigilance88 20:0ede3818e08e 456 //analyze emg (= velocity, averages?)
Vigilance88 18:44905b008f44 457
Vigilance88 18:44905b008f44 458 //calculate reference position based on the average emg (integrate)
Vigilance88 18:44905b008f44 459
Vigilance88 18:44905b008f44 460 //calculate error (refpos-currentpos) currentpos = forward kinematics
Vigilance88 18:44905b008f44 461
Vigilance88 18:44905b008f44 462 //inverse kinematics (pos error to angle error)
Vigilance88 18:44905b008f44 463
Vigilance88 18:44905b008f44 464 //PID controller
Vigilance88 24:56db31267f10 465
Vigilance88 24:56db31267f10 466 u1=pid(m1_error,m1_kp,m1_ki,m1_kd,m1_e_int,m1_e_prev); //motor 1
Vigilance88 24:56db31267f10 467 u2=pid(m2_error,m2_kp,m2_ki,m2_kd,m2_e_int,m2_e_prev); //motor 2
Vigilance88 21:d6a46315d5f5 468
Vigilance88 21:d6a46315d5f5 469 keep_in_range(&u1,-1,1); //keep u between -1 and 1, sign = direction, PWM = 0-1
Vigilance88 21:d6a46315d5f5 470 keep_in_range(&u2,-1,1);
Vigilance88 21:d6a46315d5f5 471
Vigilance88 21:d6a46315d5f5 472 //send PWM and DIR to motor 1
Vigilance88 21:d6a46315d5f5 473 dir_motor1 = u1>0 ? 1 : 0; //conditional statement dir_motor1 = [condition] ? [if met 1] : [else 0]], same as if else below.
Vigilance88 21:d6a46315d5f5 474 pwm_motor1.write(abs(u1));
Vigilance88 21:d6a46315d5f5 475
Vigilance88 21:d6a46315d5f5 476 //send PWM and DIR to motor 2
Vigilance88 25:49ccdc98639a 477 dir_motor2 = u2>0 ? 1 : 0; //conditional statement, same as if else below
Vigilance88 25:49ccdc98639a 478 pwm_motor2.write(abs(u2));
Vigilance88 21:d6a46315d5f5 479
Vigilance88 21:d6a46315d5f5 480 /*if(u1 > 0)
Vigilance88 21:d6a46315d5f5 481 {
Vigilance88 21:d6a46315d5f5 482 dir_motor1 = 0;
Vigilance88 21:d6a46315d5f5 483 else{
Vigilance88 21:d6a46315d5f5 484 dir_motor1 = 1;
Vigilance88 21:d6a46315d5f5 485 }
Vigilance88 21:d6a46315d5f5 486 }
Vigilance88 21:d6a46315d5f5 487 pwm_motor1.write(abs(u1));
Vigilance88 21:d6a46315d5f5 488
Vigilance88 21:d6a46315d5f5 489
Vigilance88 21:d6a46315d5f5 490 if(u2 > 0)
Vigilance88 21:d6a46315d5f5 491 {
Vigilance88 21:d6a46315d5f5 492 dir_motor1 = 1;
Vigilance88 21:d6a46315d5f5 493 else{
Vigilance88 21:d6a46315d5f5 494 dir_motor1 = 0;
Vigilance88 21:d6a46315d5f5 495 }
Vigilance88 21:d6a46315d5f5 496 }
Vigilance88 21:d6a46315d5f5 497 pwm_motor1.write(abs(u2));*/
Vigilance88 21:d6a46315d5f5 498
Vigilance88 18:44905b008f44 499 }
Vigilance88 18:44905b008f44 500
Vigilance88 26:fe3a5469dd6b 501 void mainMenu()
Vigilance88 26:fe3a5469dd6b 502 {
Vigilance88 26:fe3a5469dd6b 503 //Title Box
Vigilance88 26:fe3a5469dd6b 504 pc.putc(201);
Vigilance88 26:fe3a5469dd6b 505 for(int j=0;j<33;j++){
Vigilance88 26:fe3a5469dd6b 506 pc.putc(205);
Vigilance88 26:fe3a5469dd6b 507 }
Vigilance88 26:fe3a5469dd6b 508 pc.putc(187);
Vigilance88 26:fe3a5469dd6b 509 pc.printf("\n\r");
Vigilance88 26:fe3a5469dd6b 510 pc.putc(186); pc.printf(" BioRobotics M9 - Group 14 "); pc.putc(186);
Vigilance88 26:fe3a5469dd6b 511 pc.printf("\n\r");
Vigilance88 26:fe3a5469dd6b 512 pc.putc(186); pc.printf(" Robot powered ON "); pc.putc(186);
Vigilance88 26:fe3a5469dd6b 513 pc.printf("\n\r");
Vigilance88 26:fe3a5469dd6b 514 pc.putc(200);
Vigilance88 26:fe3a5469dd6b 515 for(int k=0;k<33;k++){
Vigilance88 26:fe3a5469dd6b 516 pc.putc(205);
Vigilance88 26:fe3a5469dd6b 517 }
Vigilance88 26:fe3a5469dd6b 518 pc.putc(188);
Vigilance88 26:fe3a5469dd6b 519
Vigilance88 26:fe3a5469dd6b 520 pc.printf("\n\r");
Vigilance88 26:fe3a5469dd6b 521 //endbox
Vigilance88 26:fe3a5469dd6b 522 }
Vigilance88 24:56db31267f10 523 void caliMenu(){};
Vigilance88 24:56db31267f10 524
Vigilance88 24:56db31267f10 525 //Start sampling
Vigilance88 24:56db31267f10 526 void start_sampling(void)
Vigilance88 24:56db31267f10 527 {
Vigilance88 24:56db31267f10 528 sample_timer.attach(&sample_filter,SAMPLE_RATE); //500 Hz EMG
Vigilance88 26:fe3a5469dd6b 529
Vigilance88 26:fe3a5469dd6b 530 //Debug LED will be green when sampling is active
Vigilance88 26:fe3a5469dd6b 531 green=0;
Vigilance88 25:49ccdc98639a 532 pc.printf("||- started sampling -|| \r\n");
Vigilance88 24:56db31267f10 533 }
Vigilance88 24:56db31267f10 534
Vigilance88 24:56db31267f10 535 //stop sampling
Vigilance88 24:56db31267f10 536 void stop_sampling(void)
Vigilance88 24:56db31267f10 537 {
Vigilance88 24:56db31267f10 538 sample_timer.detach();
Vigilance88 26:fe3a5469dd6b 539
Vigilance88 26:fe3a5469dd6b 540 //Debug LED will be turned off when sampling stops
Vigilance88 26:fe3a5469dd6b 541 green=1;
Vigilance88 25:49ccdc98639a 542 pc.printf("||- stopped sampling -|| \r\n");
Vigilance88 24:56db31267f10 543 }
Vigilance88 24:56db31267f10 544
Vigilance88 18:44905b008f44 545 //Start control
Vigilance88 18:44905b008f44 546 void start_control(void)
Vigilance88 18:44905b008f44 547 {
Vigilance88 25:49ccdc98639a 548 control_timer.attach(&control,SAMPLE_RATE); //100 Hz control
Vigilance88 26:fe3a5469dd6b 549
Vigilance88 26:fe3a5469dd6b 550 //Debug LED will be blue when control is on. If sampling and control are on -> blue + green = cyan.
Vigilance88 26:fe3a5469dd6b 551 blue=0;
Vigilance88 26:fe3a5469dd6b 552 pc.printf("||- started control -|| \r\n");
Vigilance88 18:44905b008f44 553 }
Vigilance88 18:44905b008f44 554
Vigilance88 18:44905b008f44 555 //stop control
Vigilance88 18:44905b008f44 556 void stop_control(void)
Vigilance88 18:44905b008f44 557 {
Vigilance88 18:44905b008f44 558 control_timer.detach();
Vigilance88 26:fe3a5469dd6b 559
Vigilance88 26:fe3a5469dd6b 560 //Debug LED will be off when control is off
Vigilance88 26:fe3a5469dd6b 561 blue=1;
Vigilance88 26:fe3a5469dd6b 562 pc.printf("||- stopped control -|| \r\n");
vsluiter 2:e314bb3b2d99 563 }
vsluiter 0:32bb76391d89 564
Vigilance88 21:d6a46315d5f5 565
Vigilance88 21:d6a46315d5f5 566 void calibrate()
vsluiter 0:32bb76391d89 567 {
Vigilance88 21:d6a46315d5f5 568
Vigilance88 21:d6a46315d5f5 569 }
tomlankhorst 15:0da764eea774 570
Vigilance88 26:fe3a5469dd6b 571 //Clears the putty (or other terminal) window
Vigilance88 26:fe3a5469dd6b 572 void clearTerminal()
Vigilance88 26:fe3a5469dd6b 573 {
Vigilance88 26:fe3a5469dd6b 574 pc.putc(27);
Vigilance88 26:fe3a5469dd6b 575 pc.printf("[2J"); // clear screen
Vigilance88 26:fe3a5469dd6b 576 pc.putc(27); // ESC
Vigilance88 26:fe3a5469dd6b 577 pc.printf("[H"); // cursor to home
Vigilance88 26:fe3a5469dd6b 578 }
Vigilance88 21:d6a46315d5f5 579
Vigilance88 21:d6a46315d5f5 580 //keeps input limited between min max
Vigilance88 24:56db31267f10 581 void keep_in_range(double * in, double min, double max)
Vigilance88 18:44905b008f44 582 {
Vigilance88 18:44905b008f44 583 *in > min ? *in < max? : *in = max: *in = min;
vsluiter 0:32bb76391d89 584 }