2nd draft
Dependencies: HIDScope MODSERIAL QEI biquadFilter mbed Servo
Fork of robot_mockup by
main.cpp@25:49ccdc98639a, 2015-10-16 (annotated)
- Committer:
- Vigilance88
- Date:
- Fri Oct 16 13:46:39 2015 +0000
- Revision:
- 25:49ccdc98639a
- Parent:
- 24:56db31267f10
- Child:
- 26:fe3a5469dd6b
calibrate emg toegevoegd
Who changed what in which revision?
User | Revision | Line number | New 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 | 25:49ccdc98639a | 27 | //Debug legs |
Vigilance88 | 25:49ccdc98639a | 28 | DigitalOut red(LED_RED); |
Vigilance88 | 25:49ccdc98639a | 29 | DigitalOut green(LED_GREEN); |
Vigilance88 | 25:49ccdc98639a | 30 | DigitalOut blue(LED_BLUE); |
Vigilance88 | 25:49ccdc98639a | 31 | |
Vigilance88 | 21:d6a46315d5f5 | 32 | //EMG shields |
Vigilance88 | 18:44905b008f44 | 33 | AnalogIn emg1(A0); //Analog input - Biceps EMG |
Vigilance88 | 18:44905b008f44 | 34 | AnalogIn emg2(A1); //Analog input - Triceps EMG |
Vigilance88 | 18:44905b008f44 | 35 | AnalogIn emg3(A2); //Analog input - Flexor EMG |
Vigilance88 | 18:44905b008f44 | 36 | AnalogIn emg4(A3); //Analog input - Extensor EMG |
Vigilance88 | 18:44905b008f44 | 37 | |
Vigilance88 | 18:44905b008f44 | 38 | Ticker sample_timer; //Ticker for EMG sampling |
Vigilance88 | 18:44905b008f44 | 39 | Ticker control_timer; //Ticker for control loop |
Vigilance88 | 18:44905b008f44 | 40 | HIDScope scope(4); //Scope 4 channels |
Vigilance88 | 18:44905b008f44 | 41 | |
Vigilance88 | 18:44905b008f44 | 42 | // AnalogIn potmeter(A4); //potmeters |
Vigilance88 | 18:44905b008f44 | 43 | // AnalogIn potmeter2(A5); // |
Vigilance88 | 18:44905b008f44 | 44 | |
Vigilance88 | 21:d6a46315d5f5 | 45 | //Encoders |
Vigilance88 | 18:44905b008f44 | 46 | QEI Encoder1(D13,D12,NC,32); //channel A and B from encoder, counts = Encoder.getPulses(); |
Vigilance88 | 18:44905b008f44 | 47 | QEI Encoder2(D10,D9,NC,32); //channel A and B from encoder, |
Vigilance88 | 21:d6a46315d5f5 | 48 | |
Vigilance88 | 21:d6a46315d5f5 | 49 | //Speed and Direction of motors - D4 (dir) and D5(speed) = motor 2, D7(dir) and D6(speed) = motor 1 |
Vigilance88 | 21:d6a46315d5f5 | 50 | PwmOut pwm_motor1(D6); //PWM motor 1 |
Vigilance88 | 21:d6a46315d5f5 | 51 | PwmOut pwm_motor2(D5); //PWM motor 2 |
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 | 25:49ccdc98639a | 56 | DigitalIn shoulder_limit(PTA4); //using FRDM buttons |
Vigilance88 | 25:49ccdc98639a | 57 | DigitalIn elbow_limit(PTC6); //using FRDM buttons |
Vigilance88 | 24:56db31267f10 | 58 | |
Vigilance88 | 21:d6a46315d5f5 | 59 | |
Vigilance88 | 21:d6a46315d5f5 | 60 | /*-------------------------------------------------------------------------------------------------------------------- |
Vigilance88 | 21:d6a46315d5f5 | 61 | ---- DECLARE VARIABLES ----------------------------------------------------------------------------------------------- |
Vigilance88 | 21:d6a46315d5f5 | 62 | --------------------------------------------------------------------------------------------------------------------*/ |
Vigilance88 | 21:d6a46315d5f5 | 63 | |
Vigilance88 | 21:d6a46315d5f5 | 64 | //EMG variables |
Vigilance88 | 24:56db31267f10 | 65 | double emg_biceps; double biceps_power; double bicepsMVC = 0; |
Vigilance88 | 24:56db31267f10 | 66 | double emg_triceps; double triceps_power; double tricepsMVC = 0; |
Vigilance88 | 24:56db31267f10 | 67 | double emg_flexor; double flexor_power; double flexorMVC = 0; |
Vigilance88 | 24:56db31267f10 | 68 | double emg_extens; double extens_power; double extensMVC = 0; |
Vigilance88 | 24:56db31267f10 | 69 | |
Vigilance88 | 25:49ccdc98639a | 70 | int muscle; |
Vigilance88 | 25:49ccdc98639a | 71 | double calibrate_time; |
Vigilance88 | 25:49ccdc98639a | 72 | |
Vigilance88 | 24:56db31267f10 | 73 | //PID variables |
Vigilance88 | 24:56db31267f10 | 74 | double u1; double u2; //Output of PID controller (PWM value for motor 1 and 2) |
Vigilance88 | 24:56db31267f10 | 75 | double m1_error=0; double m1_e_int=0; double m1_e_prev=0; //Error, integrated error, previous error |
Vigilance88 | 24:56db31267f10 | 76 | const double m1_kp=0; const double m1_ki=0; const double m1_kd=0; //Proportional, integral and derivative gains. |
Vigilance88 | 24:56db31267f10 | 77 | |
Vigilance88 | 24:56db31267f10 | 78 | double m2_error=0; double m2_e_int=0; double m2_e_prev=0; //Error, integrated error, previous error |
Vigilance88 | 24:56db31267f10 | 79 | const double m2_kp=0; const double m2_ki=0; const double m2_kd=0; //Proportional, integral and derivative gains. |
Vigilance88 | 24:56db31267f10 | 80 | |
Vigilance88 | 24:56db31267f10 | 81 | //highpass filter 20 Hz |
Vigilance88 | 24:56db31267f10 | 82 | const double high_b0 = 0.956543225556877; |
Vigilance88 | 24:56db31267f10 | 83 | const double high_b1 = -1.91308645113754; |
Vigilance88 | 24:56db31267f10 | 84 | const double high_b2 = 0.956543225556877; |
Vigilance88 | 24:56db31267f10 | 85 | const double high_a1 = -1.91197067426073; |
Vigilance88 | 24:56db31267f10 | 86 | const double high_a2 = 0.9149758348014341; |
Vigilance88 | 24:56db31267f10 | 87 | |
Vigilance88 | 24:56db31267f10 | 88 | //notchfilter 50Hz |
Vigilance88 | 24:56db31267f10 | 89 | /* ** Primary Filter (H1)** |
Vigilance88 | 24:56db31267f10 | 90 | Filter Arithmetic = Floating Point (Double Precision) |
Vigilance88 | 24:56db31267f10 | 91 | Architecture = IIR |
Vigilance88 | 24:56db31267f10 | 92 | Response = Bandstop |
Vigilance88 | 24:56db31267f10 | 93 | Method = Butterworth |
Vigilance88 | 24:56db31267f10 | 94 | Biquad = Yes |
Vigilance88 | 24:56db31267f10 | 95 | Stable = Yes |
Vigilance88 | 24:56db31267f10 | 96 | Sampling Frequency = 500Hz |
Vigilance88 | 24:56db31267f10 | 97 | Filter Order = 2 |
Vigilance88 | 24:56db31267f10 | 98 | |
Vigilance88 | 24:56db31267f10 | 99 | Band Frequencies (Hz) Att/Ripple (dB) Biquad #1 Biquad #2 |
Vigilance88 | 24:56db31267f10 | 100 | |
Vigilance88 | 24:56db31267f10 | 101 | 1 0, 48 0.001 Gain = 1.000000 Gain = 0.973674 |
Vigilance88 | 24:56db31267f10 | 102 | 2 49, 51 -60.000 B = [ 1.00000000000, -1.61816176147, 1.00000000000] B = [ 1.00000000000, -1.61816176147, 1.00000000000] |
Vigilance88 | 24:56db31267f10 | 103 | 3 52, 250 0.001 A = [ 1.00000000000, -1.58071559235, 0.97319685401] A = [ 1.00000000000, -1.61244708381, 0.97415116257] |
Vigilance88 | 24:56db31267f10 | 104 | */ |
Vigilance88 | 24:56db31267f10 | 105 | |
Vigilance88 | 24:56db31267f10 | 106 | //biquad 1 |
Vigilance88 | 24:56db31267f10 | 107 | const double notch1gain = 1.000000; |
Vigilance88 | 24:56db31267f10 | 108 | const double notch1_b0 = 1; |
Vigilance88 | 24:56db31267f10 | 109 | const double notch1_b1 = -1.61816176147 * notch1gain; |
Vigilance88 | 24:56db31267f10 | 110 | const double notch1_b2 = 1.00000000000 * notch1gain; |
Vigilance88 | 24:56db31267f10 | 111 | const double notch1_a1 = -1.58071559235 * notch1gain; |
Vigilance88 | 24:56db31267f10 | 112 | const double notch1_a2 = 0.97319685401 * notch1gain; |
Vigilance88 | 24:56db31267f10 | 113 | |
Vigilance88 | 24:56db31267f10 | 114 | //biquad 2 |
Vigilance88 | 24:56db31267f10 | 115 | const double notch2gain = 0.973674; |
Vigilance88 | 24:56db31267f10 | 116 | const double notch2_b0 = 1 * notch2gain; |
Vigilance88 | 24:56db31267f10 | 117 | const double notch2_b1 = -1.61816176147 * notch2gain; |
Vigilance88 | 24:56db31267f10 | 118 | const double notch2_b2 = 1.00000000000 * notch2gain; |
Vigilance88 | 24:56db31267f10 | 119 | const double notch2_a1 = -1.61244708381 * notch2gain; |
Vigilance88 | 24:56db31267f10 | 120 | const double notch2_a2 = 0.97415116257 * notch2gain; |
Vigilance88 | 24:56db31267f10 | 121 | |
Vigilance88 | 24:56db31267f10 | 122 | //lowpass filter 7 Hz - envelop |
Vigilance88 | 24:56db31267f10 | 123 | const double low_b0 = 0.000119046743110057; |
Vigilance88 | 24:56db31267f10 | 124 | const double low_b1 = 0.000238093486220118; |
Vigilance88 | 24:56db31267f10 | 125 | const double low_b2 = 0.000119046743110057; |
Vigilance88 | 24:56db31267f10 | 126 | const double low_a1 = -1.968902268531908; |
Vigilance88 | 24:56db31267f10 | 127 | const double low_a2 = 0.9693784555043481; |
Vigilance88 | 21:d6a46315d5f5 | 128 | |
Vigilance88 | 21:d6a46315d5f5 | 129 | |
Vigilance88 | 21:d6a46315d5f5 | 130 | |
Vigilance88 | 21:d6a46315d5f5 | 131 | /*-------------------------------------------------------------------------------------------------------------------- |
Vigilance88 | 24:56db31267f10 | 132 | ---- Filters --------------------------------------------------------------------------------------------------------- |
Vigilance88 | 21:d6a46315d5f5 | 133 | --------------------------------------------------------------------------------------------------------------------*/ |
Vigilance88 | 24:56db31267f10 | 134 | |
Vigilance88 | 24:56db31267f10 | 135 | //Using biquadFilter library |
Vigilance88 | 24:56db31267f10 | 136 | //Syntax: biquadFilter filter(a1, a2, b0, b1, b2); coefficients. Call with: filter.step(u), with u signal to be filtered. |
Vigilance88 | 24:56db31267f10 | 137 | biquadFilter highpass( high_a1 , high_a2 , high_b0 , high_b1 , high_b2 ); // removes DC and movement artefacts |
Vigilance88 | 24:56db31267f10 | 138 | biquadFilter notch1( notch1_a1 , notch1_a2 , notch1_b0 , notch1_b1 , notch1_b2 ); // removes 49-51 Hz power interference |
Vigilance88 | 24:56db31267f10 | 139 | biquadFilter notch2( notch2_a1 , notch2_a2 , notch2_b0 , notch2_b1 , notch2_b2 ); // |
Vigilance88 | 24:56db31267f10 | 140 | biquadFilter lowpass( low_a1 , low_a2 , low_b0 , low_b1 , low_b2 ); // EMG envelope |
Vigilance88 | 25:49ccdc98639a | 141 | |
Vigilance88 | 25:49ccdc98639a | 142 | biquadFilter highpass2( high_a1 , high_a2 , high_b0 , high_b1 , high_b2 ); // removes DC and movement artefacts |
Vigilance88 | 25:49ccdc98639a | 143 | biquadFilter notch1_2( notch1_a1 , notch1_a2 , notch1_b0 , notch1_b1 , notch1_b2 ); // removes 49-51 Hz power interference |
Vigilance88 | 25:49ccdc98639a | 144 | biquadFilter notch2_2( notch2_a1 , notch2_a2 , notch2_b0 , notch2_b1 , notch2_b2 ); // |
Vigilance88 | 25:49ccdc98639a | 145 | biquadFilter lowpass2( low_a1 , low_a2 , low_b0 , low_b1 , low_b2 ); // EMG envelope |
Vigilance88 | 25:49ccdc98639a | 146 | |
Vigilance88 | 25:49ccdc98639a | 147 | biquadFilter highpass3( high_a1 , high_a2 , high_b0 , high_b1 , high_b2 ); // removes DC and movement artefacts |
Vigilance88 | 25:49ccdc98639a | 148 | biquadFilter notch1_3( notch1_a1 , notch1_a2 , notch1_b0 , notch1_b1 , notch1_b2 ); // removes 49-51 Hz power interference |
Vigilance88 | 25:49ccdc98639a | 149 | biquadFilter notch2_3( notch2_a1 , notch2_a2 , notch2_b0 , notch2_b1 , notch2_b2 ); // |
Vigilance88 | 25:49ccdc98639a | 150 | biquadFilter lowpass3( low_a1 , low_a2 , low_b0 , low_b1 , low_b2 ); // EMG envelope |
Vigilance88 | 25:49ccdc98639a | 151 | |
Vigilance88 | 25:49ccdc98639a | 152 | biquadFilter highpass4( high_a1 , high_a2 , high_b0 , high_b1 , high_b2 ); // removes DC and movement artefacts |
Vigilance88 | 25:49ccdc98639a | 153 | biquadFilter notch1_4( notch1_a1 , notch1_a2 , notch1_b0 , notch1_b1 , notch1_b2 ); // removes 49-51 Hz power interference |
Vigilance88 | 25:49ccdc98639a | 154 | biquadFilter notch2_4( notch2_a1 , notch2_a2 , notch2_b0 , notch2_b1 , notch2_b2 ); // |
Vigilance88 | 25:49ccdc98639a | 155 | biquadFilter lowpass4( low_a1 , low_a2 , low_b0 , low_b1 , low_b2 ); // EMG envelope |
Vigilance88 | 25:49ccdc98639a | 156 | |
Vigilance88 | 24:56db31267f10 | 157 | biquadFilter derfilter( 0.0009446914586925257 , 0.0018893829173850514 , 0.0009446914586925257 , -1.911196288237583 , 0.914975054072353 ); // derivative filter |
Vigilance88 | 24:56db31267f10 | 158 | |
Vigilance88 | 24:56db31267f10 | 159 | /*-------------------------------------------------------------------------------------------------------------------- |
Vigilance88 | 24:56db31267f10 | 160 | ---- DECLARE FUNCTION NAMES ------------------------------------------------------------------------------------------ |
Vigilance88 | 24:56db31267f10 | 161 | --------------------------------------------------------------------------------------------------------------------*/ |
Vigilance88 | 24:56db31267f10 | 162 | void keep_in_range(double * in, double min, double max); |
Vigilance88 | 21:d6a46315d5f5 | 163 | void sample_filter(void); |
Vigilance88 | 21:d6a46315d5f5 | 164 | void control(); |
Vigilance88 | 25:49ccdc98639a | 165 | void calibrate_emg(); |
Vigilance88 | 25:49ccdc98639a | 166 | void emg_mvc(); |
Vigilance88 | 21:d6a46315d5f5 | 167 | void calibrate_arm(void); |
Vigilance88 | 21:d6a46315d5f5 | 168 | void start_sampling(void); |
Vigilance88 | 21:d6a46315d5f5 | 169 | void stop_sampling(void); |
Vigilance88 | 21:d6a46315d5f5 | 170 | void start_control(void); |
Vigilance88 | 21:d6a46315d5f5 | 171 | void stop_control(void); |
Vigilance88 | 21:d6a46315d5f5 | 172 | double pid(double error, double kp, double ki, double kd,double &e_int, double &e_prev); |
Vigilance88 | 18:44905b008f44 | 173 | |
Vigilance88 | 21:d6a46315d5f5 | 174 | void mainMenu(); |
Vigilance88 | 21:d6a46315d5f5 | 175 | void caliMenu(); |
Vigilance88 | 21:d6a46315d5f5 | 176 | |
Vigilance88 | 21:d6a46315d5f5 | 177 | /*-------------------------------------------------------------------------------------------------------------------- |
Vigilance88 | 21:d6a46315d5f5 | 178 | ---- MAIN LOOP ------------------------------------------------------------------------------------------------------- |
Vigilance88 | 21:d6a46315d5f5 | 179 | --------------------------------------------------------------------------------------------------------------------*/ |
Vigilance88 | 21:d6a46315d5f5 | 180 | |
Vigilance88 | 21:d6a46315d5f5 | 181 | int main() |
Vigilance88 | 21:d6a46315d5f5 | 182 | { |
Vigilance88 | 24:56db31267f10 | 183 | pc.baud(115200); |
Vigilance88 | 25:49ccdc98639a | 184 | red=1; green=1; blue=1; |
Vigilance88 | 24:56db31267f10 | 185 | // make a menu, user has to initiate next step |
Vigilance88 | 25:49ccdc98639a | 186 | //mainMenu(); |
Vigilance88 | 25:49ccdc98639a | 187 | //caliMenu(); // Menu function |
Vigilance88 | 25:49ccdc98639a | 188 | //calibrate_arm(); //Start Calibration |
Vigilance88 | 25:49ccdc98639a | 189 | |
Vigilance88 | 25:49ccdc98639a | 190 | calibrate_emg(); |
Vigilance88 | 25:49ccdc98639a | 191 | |
Vigilance88 | 25:49ccdc98639a | 192 | //start_control(); //100 Hz control |
Vigilance88 | 21:d6a46315d5f5 | 193 | |
Vigilance88 | 21:d6a46315d5f5 | 194 | //maybe some stop commands when a button is pressed: detach from timers. |
Vigilance88 | 21:d6a46315d5f5 | 195 | //stop_control(); |
Vigilance88 | 21:d6a46315d5f5 | 196 | //stop_sampling(); |
Vigilance88 | 21:d6a46315d5f5 | 197 | |
Vigilance88 | 21:d6a46315d5f5 | 198 | while(1) { |
Vigilance88 | 25:49ccdc98639a | 199 | |
Vigilance88 | 21:d6a46315d5f5 | 200 | } |
Vigilance88 | 21:d6a46315d5f5 | 201 | //end of while loop |
Vigilance88 | 21:d6a46315d5f5 | 202 | } |
Vigilance88 | 21:d6a46315d5f5 | 203 | //end of main |
Vigilance88 | 21:d6a46315d5f5 | 204 | |
Vigilance88 | 21:d6a46315d5f5 | 205 | /*-------------------------------------------------------------------------------------------------------------------- |
Vigilance88 | 21:d6a46315d5f5 | 206 | ---- FUNCTIONS ------------------------------------------------------------------------------------------------------- |
Vigilance88 | 21:d6a46315d5f5 | 207 | --------------------------------------------------------------------------------------------------------------------*/ |
Vigilance88 | 18:44905b008f44 | 208 | |
Vigilance88 | 21:d6a46315d5f5 | 209 | //Sample and Filter |
Vigilance88 | 21:d6a46315d5f5 | 210 | void sample_filter(void) |
Vigilance88 | 18:44905b008f44 | 211 | { |
Vigilance88 | 21:d6a46315d5f5 | 212 | double emg_biceps = emg1.read(); //Biceps |
Vigilance88 | 21:d6a46315d5f5 | 213 | double emg_triceps = emg2.read(); //Triceps |
Vigilance88 | 21:d6a46315d5f5 | 214 | double emg_flexor = emg3.read(); //Flexor |
Vigilance88 | 21:d6a46315d5f5 | 215 | double emg_extens = emg4.read(); //Extensor |
Vigilance88 | 21:d6a46315d5f5 | 216 | |
Vigilance88 | 21:d6a46315d5f5 | 217 | //Filter: high-pass -> notch -> rectify -> lowpass or moving average |
Vigilance88 | 22:1ba637601dc3 | 218 | // Can we use same biquadFilter (eg. highpass) for other muscles or does each muscle need its own biquad? |
Vigilance88 | 25:49ccdc98639a | 219 | 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 | 220 | 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 | 221 | 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 | 222 | biceps_power = abs(biceps_power); triceps_power = abs(triceps_power); flexor_power = abs(flexor_power); extens_power = abs(extens_power); |
Vigilance88 | 25:49ccdc98639a | 223 | 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 | 224 | |
Vigilance88 | 21:d6a46315d5f5 | 225 | |
Vigilance88 | 21:d6a46315d5f5 | 226 | /* alternative for lowpass filter: moving average |
Vigilance88 | 21:d6a46315d5f5 | 227 | window=30; //30 samples |
Vigilance88 | 21:d6a46315d5f5 | 228 | int i=0; //buffer index |
Vigilance88 | 21:d6a46315d5f5 | 229 | bicepsbuffer[i]=biceps_power //fill array |
Vigilance88 | 21:d6a46315d5f5 | 230 | |
Vigilance88 | 21:d6a46315d5f5 | 231 | i++; |
Vigilance88 | 21:d6a46315d5f5 | 232 | if(i==window){ |
Vigilance88 | 21:d6a46315d5f5 | 233 | i=0; |
Vigilance88 | 21:d6a46315d5f5 | 234 | } |
Vigilance88 | 21:d6a46315d5f5 | 235 | |
Vigilance88 | 24:56db31267f10 | 236 | for(int x = 0; x < window; x++){ |
Vigilance88 | 24:56db31267f10 | 237 | avg1 += bicepsbuffer[x]; |
Vigilance88 | 24:56db31267f10 | 238 | } |
Vigilance88 | 24:56db31267f10 | 239 | avg1 = avg1/window; |
Vigilance88 | 21:d6a46315d5f5 | 240 | */ |
Vigilance88 | 21:d6a46315d5f5 | 241 | |
Vigilance88 | 18:44905b008f44 | 242 | } |
Vigilance88 | 18:44905b008f44 | 243 | |
Vigilance88 | 18:44905b008f44 | 244 | //Send arm to mechanical limits, and set encoder to 0. Then send arm to starting position. |
Vigilance88 | 19:0a3ee31dcdb4 | 245 | void calibrate_arm(void) |
Vigilance88 | 19:0a3ee31dcdb4 | 246 | { |
Vigilance88 | 25:49ccdc98639a | 247 | //const double hit = 0.5; |
Vigilance88 | 22:1ba637601dc3 | 248 | dir_motor1=1; //ccw |
Vigilance88 | 22:1ba637601dc3 | 249 | dir_motor2=1; //ccw |
Vigilance88 | 25:49ccdc98639a | 250 | pwm_motor1.write(0.2f); //move upper arm slowly ccw |
Vigilance88 | 25:49ccdc98639a | 251 | pwm_motor2.write(0.2f); //move forearm slowly ccw |
Vigilance88 | 25:49ccdc98639a | 252 | |
Vigilance88 | 25:49ccdc98639a | 253 | if(shoulder_limit.read() < 0.5){ //when limit switches are hit, stop motor and reset encoder |
Vigilance88 | 25:49ccdc98639a | 254 | pwm_motor1.write(0); |
Vigilance88 | 25:49ccdc98639a | 255 | Encoder1.reset(); |
Vigilance88 | 25:49ccdc98639a | 256 | } |
Vigilance88 | 25:49ccdc98639a | 257 | if(elbow_limit.read() < 0.5){ |
Vigilance88 | 25:49ccdc98639a | 258 | pwm_motor2.write(0); |
Vigilance88 | 25:49ccdc98639a | 259 | Encoder2.reset(); |
Vigilance88 | 25:49ccdc98639a | 260 | } |
Vigilance88 | 25:49ccdc98639a | 261 | |
Vigilance88 | 25:49ccdc98639a | 262 | /* while(shoulder_limit != hit){ |
Vigilance88 | 22:1ba637601dc3 | 263 | pwm_motor1.write(0.4); |
Vigilance88 | 24:56db31267f10 | 264 | } |
Vigilance88 | 24:56db31267f10 | 265 | Encoder1.reset(); |
Vigilance88 | 24:56db31267f10 | 266 | |
Vigilance88 | 24:56db31267f10 | 267 | while(elbow_limit != hit){ |
Vigilance88 | 22:1ba637601dc3 | 268 | pwm_motor2.write(0.4); |
Vigilance88 | 22:1ba637601dc3 | 269 | } |
Vigilance88 | 24:56db31267f10 | 270 | Encoder2.reset(); |
Vigilance88 | 25:49ccdc98639a | 271 | */ |
Vigilance88 | 19:0a3ee31dcdb4 | 272 | } |
Vigilance88 | 19:0a3ee31dcdb4 | 273 | |
Vigilance88 | 21:d6a46315d5f5 | 274 | //EMG Maximum Voluntary Contraction measurement |
Vigilance88 | 25:49ccdc98639a | 275 | void emg_mvc() |
Vigilance88 | 25:49ccdc98639a | 276 | { |
Vigilance88 | 24:56db31267f10 | 277 | //double sampletime=0; |
Vigilance88 | 24:56db31267f10 | 278 | //sampletime=+SAMPLE_RATE; |
Vigilance88 | 24:56db31267f10 | 279 | // |
Vigilance88 | 24:56db31267f10 | 280 | // if(sampletime<5) |
Vigilance88 | 25:49ccdc98639a | 281 | //int muscle=1; |
Vigilance88 | 25:49ccdc98639a | 282 | //for(int index=0; index<2500;index++){ //measure 5 seconds@500hz = 2500 samples |
Vigilance88 | 25:49ccdc98639a | 283 | |
Vigilance88 | 24:56db31267f10 | 284 | if(muscle==1){ |
Vigilance88 | 24:56db31267f10 | 285 | |
Vigilance88 | 24:56db31267f10 | 286 | if(biceps_power>bicepsMVC){ |
Vigilance88 | 25:49ccdc98639a | 287 | printf("+ "); |
Vigilance88 | 21:d6a46315d5f5 | 288 | bicepsMVC=biceps_power; |
Vigilance88 | 24:56db31267f10 | 289 | } |
Vigilance88 | 25:49ccdc98639a | 290 | else |
Vigilance88 | 25:49ccdc98639a | 291 | printf("- "); |
Vigilance88 | 24:56db31267f10 | 292 | } |
Vigilance88 | 24:56db31267f10 | 293 | |
Vigilance88 | 24:56db31267f10 | 294 | if(muscle==2){ |
Vigilance88 | 24:56db31267f10 | 295 | |
Vigilance88 | 24:56db31267f10 | 296 | if(triceps_power>tricepsMVC){ |
Vigilance88 | 24:56db31267f10 | 297 | tricepsMVC=triceps_power; |
Vigilance88 | 24:56db31267f10 | 298 | } |
Vigilance88 | 24:56db31267f10 | 299 | } |
Vigilance88 | 24:56db31267f10 | 300 | |
Vigilance88 | 24:56db31267f10 | 301 | if(muscle==3){ |
Vigilance88 | 24:56db31267f10 | 302 | |
Vigilance88 | 24:56db31267f10 | 303 | if(flexor_power>flexorMVC){ |
Vigilance88 | 24:56db31267f10 | 304 | flexorMVC=flexor_power; |
Vigilance88 | 24:56db31267f10 | 305 | } |
Vigilance88 | 24:56db31267f10 | 306 | } |
Vigilance88 | 24:56db31267f10 | 307 | |
Vigilance88 | 24:56db31267f10 | 308 | if(muscle==4){ |
Vigilance88 | 24:56db31267f10 | 309 | |
Vigilance88 | 24:56db31267f10 | 310 | if(extens_power>extensMVC){ |
Vigilance88 | 24:56db31267f10 | 311 | extensMVC=extens_power; |
Vigilance88 | 24:56db31267f10 | 312 | } |
Vigilance88 | 24:56db31267f10 | 313 | } |
Vigilance88 | 25:49ccdc98639a | 314 | |
Vigilance88 | 25:49ccdc98639a | 315 | //} |
Vigilance88 | 25:49ccdc98639a | 316 | calibrate_time = calibrate_time + 0.002; |
Vigilance88 | 25:49ccdc98639a | 317 | |
Vigilance88 | 25:49ccdc98639a | 318 | |
Vigilance88 | 25:49ccdc98639a | 319 | |
Vigilance88 | 25:49ccdc98639a | 320 | } |
Vigilance88 | 25:49ccdc98639a | 321 | |
Vigilance88 | 25:49ccdc98639a | 322 | //EMG calibration |
Vigilance88 | 25:49ccdc98639a | 323 | void calibrate_emg() |
Vigilance88 | 25:49ccdc98639a | 324 | { |
Vigilance88 | 25:49ccdc98639a | 325 | Ticker timer; |
Vigilance88 | 25:49ccdc98639a | 326 | |
Vigilance88 | 25:49ccdc98639a | 327 | pc.printf("|-- Robot Started --| \r\n"); |
Vigilance88 | 25:49ccdc98639a | 328 | pc.printf("Testcode calibration \r\n"); |
Vigilance88 | 25:49ccdc98639a | 329 | wait(1); |
Vigilance88 | 25:49ccdc98639a | 330 | pc.printf("+ means current sample is higher than stored MVC\r\n"); |
Vigilance88 | 25:49ccdc98639a | 331 | pc.printf("- means current sample is lower than stored MVC\r\n"); |
Vigilance88 | 25:49ccdc98639a | 332 | wait(3); |
Vigilance88 | 25:49ccdc98639a | 333 | pc.printf(" Biceps is first. "); wait(1); |
Vigilance88 | 25:49ccdc98639a | 334 | pc.printf(" Press any key to begin... "); wait(1); |
Vigilance88 | 25:49ccdc98639a | 335 | char input; |
Vigilance88 | 25:49ccdc98639a | 336 | input=pc.getc(); |
Vigilance88 | 25:49ccdc98639a | 337 | pc.putc(input); |
Vigilance88 | 25:49ccdc98639a | 338 | pc.printf(" \r\n Starting in 3... \r\n"); wait(1); |
Vigilance88 | 25:49ccdc98639a | 339 | pc.printf(" \r\n Starting in 2... \r\n"); wait(1); |
Vigilance88 | 25:49ccdc98639a | 340 | pc.printf(" \r\n Starting in 1... \r\n"); wait(1); |
Vigilance88 | 25:49ccdc98639a | 341 | |
Vigilance88 | 25:49ccdc98639a | 342 | start_sampling(); |
Vigilance88 | 25:49ccdc98639a | 343 | muscle=1; |
Vigilance88 | 25:49ccdc98639a | 344 | timer.attach(&emg_mvc,0.002); |
Vigilance88 | 25:49ccdc98639a | 345 | wait(5); |
Vigilance88 | 25:49ccdc98639a | 346 | timer.detach(); |
Vigilance88 | 25:49ccdc98639a | 347 | pc.printf("\r\n MVC = %f \r\n",bicepsMVC); |
Vigilance88 | 25:49ccdc98639a | 348 | |
Vigilance88 | 25:49ccdc98639a | 349 | pc.printf("Calibrate_emg() exited \r\n"); |
Vigilance88 | 25:49ccdc98639a | 350 | pc.printf("Measured time: %f seconds \r\n",calibrate_time); |
Vigilance88 | 25:49ccdc98639a | 351 | calibrate_time=0; |
Vigilance88 | 25:49ccdc98639a | 352 | |
Vigilance88 | 25:49ccdc98639a | 353 | // Triceps: |
Vigilance88 | 25:49ccdc98639a | 354 | pc.printf(" Triceps is next "); wait(1); |
Vigilance88 | 25:49ccdc98639a | 355 | pc.printf(" Press any key to begin... "); wait(1); |
Vigilance88 | 25:49ccdc98639a | 356 | input=pc.getc(); |
Vigilance88 | 25:49ccdc98639a | 357 | pc.putc(input); |
Vigilance88 | 25:49ccdc98639a | 358 | pc.printf(" \r\n Starting in 3... \r\n"); wait(1); |
Vigilance88 | 25:49ccdc98639a | 359 | pc.printf(" \r\n Starting in 2... \r\n"); wait(1); |
Vigilance88 | 25:49ccdc98639a | 360 | pc.printf(" \r\n Starting in 1... \r\n"); wait(1); |
Vigilance88 | 25:49ccdc98639a | 361 | start_sampling(); |
Vigilance88 | 25:49ccdc98639a | 362 | muscle=1; |
Vigilance88 | 25:49ccdc98639a | 363 | timer.attach(&emg_mvc,0.002); |
Vigilance88 | 25:49ccdc98639a | 364 | wait(5); |
Vigilance88 | 25:49ccdc98639a | 365 | timer.detach(); |
Vigilance88 | 25:49ccdc98639a | 366 | pc.printf("\r\n Triceps MVC = %f \r\n",tricepsMVC); |
Vigilance88 | 25:49ccdc98639a | 367 | |
Vigilance88 | 25:49ccdc98639a | 368 | pc.printf("Calibrate_emg() exited \r\n"); |
Vigilance88 | 25:49ccdc98639a | 369 | pc.printf("Measured time: %f seconds \r\n",calibrate_time); |
Vigilance88 | 25:49ccdc98639a | 370 | calibrate_time=0; |
Vigilance88 | 25:49ccdc98639a | 371 | |
Vigilance88 | 25:49ccdc98639a | 372 | //Flexor: |
Vigilance88 | 25:49ccdc98639a | 373 | |
Vigilance88 | 25:49ccdc98639a | 374 | //Extensor: |
Vigilance88 | 25:49ccdc98639a | 375 | |
Vigilance88 | 25:49ccdc98639a | 376 | stop_sampling(); |
Vigilance88 | 24:56db31267f10 | 377 | |
Vigilance88 | 18:44905b008f44 | 378 | } |
Vigilance88 | 18:44905b008f44 | 379 | |
Vigilance88 | 18:44905b008f44 | 380 | |
Vigilance88 | 18:44905b008f44 | 381 | //Input error and Kp, Kd, Ki, output control signal |
Vigilance88 | 20:0ede3818e08e | 382 | double pid(double error, double kp, double ki, double kd,double &e_int, double &e_prev) |
vsluiter | 2:e314bb3b2d99 | 383 | { |
Vigilance88 | 20:0ede3818e08e | 384 | // Derivative |
Vigilance88 | 24:56db31267f10 | 385 | double e_der = (error-e_prev)/ CONTROL_RATE; |
Vigilance88 | 21:d6a46315d5f5 | 386 | e_der = derfilter.step(e_der); |
Vigilance88 | 21:d6a46315d5f5 | 387 | e_prev = error; |
Vigilance88 | 20:0ede3818e08e | 388 | // Integral |
Vigilance88 | 24:56db31267f10 | 389 | e_int = e_int + CONTROL_RATE * error; |
Vigilance88 | 20:0ede3818e08e | 390 | // PID |
Vigilance88 | 21:d6a46315d5f5 | 391 | return kp*error + ki*e_int + kd * e_der; |
Vigilance88 | 20:0ede3818e08e | 392 | |
Vigilance88 | 18:44905b008f44 | 393 | } |
Vigilance88 | 18:44905b008f44 | 394 | |
Vigilance88 | 20:0ede3818e08e | 395 | //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 | 396 | void control() |
Vigilance88 | 18:44905b008f44 | 397 | { |
Vigilance88 | 20:0ede3818e08e | 398 | //analyze emg (= velocity, averages?) |
Vigilance88 | 18:44905b008f44 | 399 | |
Vigilance88 | 18:44905b008f44 | 400 | //calculate reference position based on the average emg (integrate) |
Vigilance88 | 18:44905b008f44 | 401 | |
Vigilance88 | 18:44905b008f44 | 402 | //calculate error (refpos-currentpos) currentpos = forward kinematics |
Vigilance88 | 18:44905b008f44 | 403 | |
Vigilance88 | 18:44905b008f44 | 404 | //inverse kinematics (pos error to angle error) |
Vigilance88 | 18:44905b008f44 | 405 | |
Vigilance88 | 18:44905b008f44 | 406 | //PID controller |
Vigilance88 | 24:56db31267f10 | 407 | |
Vigilance88 | 24:56db31267f10 | 408 | u1=pid(m1_error,m1_kp,m1_ki,m1_kd,m1_e_int,m1_e_prev); //motor 1 |
Vigilance88 | 24:56db31267f10 | 409 | u2=pid(m2_error,m2_kp,m2_ki,m2_kd,m2_e_int,m2_e_prev); //motor 2 |
Vigilance88 | 21:d6a46315d5f5 | 410 | |
Vigilance88 | 21:d6a46315d5f5 | 411 | keep_in_range(&u1,-1,1); //keep u between -1 and 1, sign = direction, PWM = 0-1 |
Vigilance88 | 21:d6a46315d5f5 | 412 | keep_in_range(&u2,-1,1); |
Vigilance88 | 21:d6a46315d5f5 | 413 | |
Vigilance88 | 21:d6a46315d5f5 | 414 | //send PWM and DIR to motor 1 |
Vigilance88 | 21:d6a46315d5f5 | 415 | dir_motor1 = u1>0 ? 1 : 0; //conditional statement dir_motor1 = [condition] ? [if met 1] : [else 0]], same as if else below. |
Vigilance88 | 21:d6a46315d5f5 | 416 | pwm_motor1.write(abs(u1)); |
Vigilance88 | 21:d6a46315d5f5 | 417 | |
Vigilance88 | 21:d6a46315d5f5 | 418 | //send PWM and DIR to motor 2 |
Vigilance88 | 25:49ccdc98639a | 419 | dir_motor2 = u2>0 ? 1 : 0; //conditional statement, same as if else below |
Vigilance88 | 25:49ccdc98639a | 420 | pwm_motor2.write(abs(u2)); |
Vigilance88 | 21:d6a46315d5f5 | 421 | |
Vigilance88 | 21:d6a46315d5f5 | 422 | /*if(u1 > 0) |
Vigilance88 | 21:d6a46315d5f5 | 423 | { |
Vigilance88 | 21:d6a46315d5f5 | 424 | dir_motor1 = 0; |
Vigilance88 | 21:d6a46315d5f5 | 425 | else{ |
Vigilance88 | 21:d6a46315d5f5 | 426 | dir_motor1 = 1; |
Vigilance88 | 21:d6a46315d5f5 | 427 | } |
Vigilance88 | 21:d6a46315d5f5 | 428 | } |
Vigilance88 | 21:d6a46315d5f5 | 429 | pwm_motor1.write(abs(u1)); |
Vigilance88 | 21:d6a46315d5f5 | 430 | |
Vigilance88 | 21:d6a46315d5f5 | 431 | |
Vigilance88 | 21:d6a46315d5f5 | 432 | if(u2 > 0) |
Vigilance88 | 21:d6a46315d5f5 | 433 | { |
Vigilance88 | 21:d6a46315d5f5 | 434 | dir_motor1 = 1; |
Vigilance88 | 21:d6a46315d5f5 | 435 | else{ |
Vigilance88 | 21:d6a46315d5f5 | 436 | dir_motor1 = 0; |
Vigilance88 | 21:d6a46315d5f5 | 437 | } |
Vigilance88 | 21:d6a46315d5f5 | 438 | } |
Vigilance88 | 21:d6a46315d5f5 | 439 | pwm_motor1.write(abs(u2));*/ |
Vigilance88 | 21:d6a46315d5f5 | 440 | |
Vigilance88 | 18:44905b008f44 | 441 | } |
Vigilance88 | 18:44905b008f44 | 442 | |
Vigilance88 | 24:56db31267f10 | 443 | void mainMenu(){}; |
Vigilance88 | 24:56db31267f10 | 444 | void caliMenu(){}; |
Vigilance88 | 24:56db31267f10 | 445 | |
Vigilance88 | 24:56db31267f10 | 446 | //Start sampling |
Vigilance88 | 24:56db31267f10 | 447 | void start_sampling(void) |
Vigilance88 | 24:56db31267f10 | 448 | { |
Vigilance88 | 24:56db31267f10 | 449 | sample_timer.attach(&sample_filter,SAMPLE_RATE); //500 Hz EMG |
Vigilance88 | 25:49ccdc98639a | 450 | blue=0; green=0; |
Vigilance88 | 25:49ccdc98639a | 451 | pc.printf("||- started sampling -|| \r\n"); |
Vigilance88 | 24:56db31267f10 | 452 | } |
Vigilance88 | 24:56db31267f10 | 453 | |
Vigilance88 | 24:56db31267f10 | 454 | //stop sampling |
Vigilance88 | 24:56db31267f10 | 455 | void stop_sampling(void) |
Vigilance88 | 24:56db31267f10 | 456 | { |
Vigilance88 | 24:56db31267f10 | 457 | sample_timer.detach(); |
Vigilance88 | 25:49ccdc98639a | 458 | blue=1; green=1; |
Vigilance88 | 25:49ccdc98639a | 459 | pc.printf("||- stopped sampling -|| \r\n"); |
Vigilance88 | 24:56db31267f10 | 460 | } |
Vigilance88 | 24:56db31267f10 | 461 | |
Vigilance88 | 18:44905b008f44 | 462 | //Start control |
Vigilance88 | 18:44905b008f44 | 463 | void start_control(void) |
Vigilance88 | 18:44905b008f44 | 464 | { |
Vigilance88 | 25:49ccdc98639a | 465 | control_timer.attach(&control,SAMPLE_RATE); //100 Hz control |
Vigilance88 | 18:44905b008f44 | 466 | } |
Vigilance88 | 18:44905b008f44 | 467 | |
Vigilance88 | 18:44905b008f44 | 468 | //stop control |
Vigilance88 | 18:44905b008f44 | 469 | void stop_control(void) |
Vigilance88 | 18:44905b008f44 | 470 | { |
Vigilance88 | 18:44905b008f44 | 471 | control_timer.detach(); |
vsluiter | 2:e314bb3b2d99 | 472 | } |
vsluiter | 0:32bb76391d89 | 473 | |
Vigilance88 | 21:d6a46315d5f5 | 474 | |
Vigilance88 | 21:d6a46315d5f5 | 475 | void calibrate() |
vsluiter | 0:32bb76391d89 | 476 | { |
Vigilance88 | 21:d6a46315d5f5 | 477 | |
Vigilance88 | 21:d6a46315d5f5 | 478 | } |
tomlankhorst | 15:0da764eea774 | 479 | |
Vigilance88 | 21:d6a46315d5f5 | 480 | |
Vigilance88 | 21:d6a46315d5f5 | 481 | //keeps input limited between min max |
Vigilance88 | 24:56db31267f10 | 482 | void keep_in_range(double * in, double min, double max) |
Vigilance88 | 18:44905b008f44 | 483 | { |
Vigilance88 | 18:44905b008f44 | 484 | *in > min ? *in < max? : *in = max: *in = min; |
vsluiter | 0:32bb76391d89 | 485 | } |