2nd draft
Dependencies: HIDScope MODSERIAL QEI biquadFilter mbed Servo
Fork of robot_mockup by
main.cpp@27:d1814e271a95, 2015-10-19 (annotated)
- Committer:
- Vigilance88
- Date:
- Mon Oct 19 08:34:24 2015 +0000
- Revision:
- 27:d1814e271a95
- Parent:
- 26:fe3a5469dd6b
- Child:
- 28:743485bb51e4
added calibrate_arm & control testcode
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 | 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 | 27:d1814e271a95 | 231 | //calibrate_emg(); |
Vigilance88 | 27:d1814e271a95 | 232 | wait(3); |
Vigilance88 | 27:d1814e271a95 | 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 | 27:d1814e271a95 | 239 | char c; |
Vigilance88 | 27:d1814e271a95 | 240 | pc.printf("entering while loop \r\n"); |
Vigilance88 | 27:d1814e271a95 | 241 | |
Vigilance88 | 21:d6a46315d5f5 | 242 | while(1) { |
Vigilance88 | 27:d1814e271a95 | 243 | |
Vigilance88 | 27:d1814e271a95 | 244 | if( pc.readable() ){ |
Vigilance88 | 27:d1814e271a95 | 245 | c = pc.getc(); |
Vigilance88 | 27:d1814e271a95 | 246 | switch (c) |
Vigilance88 | 27:d1814e271a95 | 247 | { |
Vigilance88 | 27:d1814e271a95 | 248 | case '1' : |
Vigilance88 | 27:d1814e271a95 | 249 | x = x + 0.01; |
Vigilance88 | 27:d1814e271a95 | 250 | //controlMenu(); |
Vigilance88 | 27:d1814e271a95 | 251 | //running=false; |
Vigilance88 | 27:d1814e271a95 | 252 | break; |
Vigilance88 | 27:d1814e271a95 | 253 | |
Vigilance88 | 27:d1814e271a95 | 254 | case '2' : |
Vigilance88 | 27:d1814e271a95 | 255 | x-=0.01; |
Vigilance88 | 27:d1814e271a95 | 256 | //controlMenu(); |
Vigilance88 | 27:d1814e271a95 | 257 | //running=false; |
Vigilance88 | 27:d1814e271a95 | 258 | break; |
Vigilance88 | 27:d1814e271a95 | 259 | |
Vigilance88 | 27:d1814e271a95 | 260 | case '3' : |
Vigilance88 | 27:d1814e271a95 | 261 | y+=0.01; |
Vigilance88 | 27:d1814e271a95 | 262 | //controlMenu(); |
Vigilance88 | 27:d1814e271a95 | 263 | //running=false; |
Vigilance88 | 27:d1814e271a95 | 264 | break; |
Vigilance88 | 27:d1814e271a95 | 265 | |
Vigilance88 | 27:d1814e271a95 | 266 | |
Vigilance88 | 27:d1814e271a95 | 267 | case '4' : |
Vigilance88 | 27:d1814e271a95 | 268 | y-=0.01; |
Vigilance88 | 27:d1814e271a95 | 269 | //controlMenu(); |
Vigilance88 | 27:d1814e271a95 | 270 | //running=false; |
Vigilance88 | 27:d1814e271a95 | 271 | break; |
Vigilance88 | 27:d1814e271a95 | 272 | |
Vigilance88 | 27:d1814e271a95 | 273 | case 'q' : |
Vigilance88 | 27:d1814e271a95 | 274 | pc.printf("Quit"); |
Vigilance88 | 27:d1814e271a95 | 275 | //running = false; |
Vigilance88 | 27:d1814e271a95 | 276 | break; |
Vigilance88 | 27:d1814e271a95 | 277 | }//end switch |
Vigilance88 | 27:d1814e271a95 | 278 | pc.printf("Reference position: %f and %f \r\n",x,y); |
Vigilance88 | 27:d1814e271a95 | 279 | pc.printf("Current position: %f and %f \r\n",current_x,current_y); |
Vigilance88 | 27:d1814e271a95 | 280 | pc.printf("Current angles: %f and %f \r\n",theta1,theta2); |
Vigilance88 | 27:d1814e271a95 | 281 | pc.printf("Error in angles: %f and %f \r\n",dtheta1,dtheta2); |
Vigilance88 | 27:d1814e271a95 | 282 | pc.printf("PID output: %f and %f \r\n",u1,u2); |
Vigilance88 | 27:d1814e271a95 | 283 | pc.printf("----------------------------------------\r\n\n"); |
Vigilance88 | 27:d1814e271a95 | 284 | } |
Vigilance88 | 27:d1814e271a95 | 285 | //end if |
Vigilance88 | 21:d6a46315d5f5 | 286 | } |
Vigilance88 | 21:d6a46315d5f5 | 287 | //end of while loop |
Vigilance88 | 21:d6a46315d5f5 | 288 | } |
Vigilance88 | 21:d6a46315d5f5 | 289 | //end of main |
Vigilance88 | 21:d6a46315d5f5 | 290 | |
Vigilance88 | 21:d6a46315d5f5 | 291 | /*-------------------------------------------------------------------------------------------------------------------- |
Vigilance88 | 21:d6a46315d5f5 | 292 | ---- FUNCTIONS ------------------------------------------------------------------------------------------------------- |
Vigilance88 | 21:d6a46315d5f5 | 293 | --------------------------------------------------------------------------------------------------------------------*/ |
Vigilance88 | 18:44905b008f44 | 294 | |
Vigilance88 | 21:d6a46315d5f5 | 295 | //Sample and Filter |
Vigilance88 | 21:d6a46315d5f5 | 296 | void sample_filter(void) |
Vigilance88 | 18:44905b008f44 | 297 | { |
Vigilance88 | 21:d6a46315d5f5 | 298 | double emg_biceps = emg1.read(); //Biceps |
Vigilance88 | 21:d6a46315d5f5 | 299 | double emg_triceps = emg2.read(); //Triceps |
Vigilance88 | 21:d6a46315d5f5 | 300 | double emg_flexor = emg3.read(); //Flexor |
Vigilance88 | 21:d6a46315d5f5 | 301 | double emg_extens = emg4.read(); //Extensor |
Vigilance88 | 21:d6a46315d5f5 | 302 | |
Vigilance88 | 21:d6a46315d5f5 | 303 | //Filter: high-pass -> notch -> rectify -> lowpass or moving average |
Vigilance88 | 22:1ba637601dc3 | 304 | // Can we use same biquadFilter (eg. highpass) for other muscles or does each muscle need its own biquad? |
Vigilance88 | 25:49ccdc98639a | 305 | 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 | 306 | 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 | 307 | 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 | 308 | biceps_power = abs(biceps_power); triceps_power = abs(triceps_power); flexor_power = abs(flexor_power); extens_power = abs(extens_power); |
Vigilance88 | 25:49ccdc98639a | 309 | 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 | 310 | |
Vigilance88 | 21:d6a46315d5f5 | 311 | |
Vigilance88 | 21:d6a46315d5f5 | 312 | /* alternative for lowpass filter: moving average |
Vigilance88 | 21:d6a46315d5f5 | 313 | window=30; //30 samples |
Vigilance88 | 21:d6a46315d5f5 | 314 | int i=0; //buffer index |
Vigilance88 | 21:d6a46315d5f5 | 315 | bicepsbuffer[i]=biceps_power //fill array |
Vigilance88 | 21:d6a46315d5f5 | 316 | |
Vigilance88 | 21:d6a46315d5f5 | 317 | i++; |
Vigilance88 | 21:d6a46315d5f5 | 318 | if(i==window){ |
Vigilance88 | 21:d6a46315d5f5 | 319 | i=0; |
Vigilance88 | 21:d6a46315d5f5 | 320 | } |
Vigilance88 | 21:d6a46315d5f5 | 321 | |
Vigilance88 | 24:56db31267f10 | 322 | for(int x = 0; x < window; x++){ |
Vigilance88 | 24:56db31267f10 | 323 | avg1 += bicepsbuffer[x]; |
Vigilance88 | 24:56db31267f10 | 324 | } |
Vigilance88 | 24:56db31267f10 | 325 | avg1 = avg1/window; |
Vigilance88 | 21:d6a46315d5f5 | 326 | */ |
Vigilance88 | 21:d6a46315d5f5 | 327 | |
Vigilance88 | 18:44905b008f44 | 328 | } |
Vigilance88 | 18:44905b008f44 | 329 | |
Vigilance88 | 27:d1814e271a95 | 330 | void controlMenu() |
Vigilance88 | 27:d1814e271a95 | 331 | { |
Vigilance88 | 27:d1814e271a95 | 332 | pc.printf("1) Move Arm Left\r\n"); |
Vigilance88 | 27:d1814e271a95 | 333 | pc.printf("2) Move Arm Right\r\n"); |
Vigilance88 | 27:d1814e271a95 | 334 | pc.printf("3) Move Arm Up\r\n"); |
Vigilance88 | 27:d1814e271a95 | 335 | pc.printf("4) Move Arm Down\r\n"); |
Vigilance88 | 27:d1814e271a95 | 336 | pc.printf("q) Exit \r\n"); |
Vigilance88 | 27:d1814e271a95 | 337 | pc.printf("Please make a choice => \r\n"); |
Vigilance88 | 27:d1814e271a95 | 338 | } |
Vigilance88 | 27:d1814e271a95 | 339 | |
Vigilance88 | 18:44905b008f44 | 340 | //Send arm to mechanical limits, and set encoder to 0. Then send arm to starting position. |
Vigilance88 | 19:0a3ee31dcdb4 | 341 | void calibrate_arm(void) |
Vigilance88 | 19:0a3ee31dcdb4 | 342 | { |
Vigilance88 | 27:d1814e271a95 | 343 | pc.printf("Calibrate_arm() entered\r\n"); |
Vigilance88 | 26:fe3a5469dd6b | 344 | bool calibrating = true; |
Vigilance88 | 26:fe3a5469dd6b | 345 | bool done1 = false; |
Vigilance88 | 26:fe3a5469dd6b | 346 | bool done2 = false; |
Vigilance88 | 27:d1814e271a95 | 347 | pc.printf("To start arm calibration, press any key =>"); |
Vigilance88 | 27:d1814e271a95 | 348 | pc.getc(); |
Vigilance88 | 27:d1814e271a95 | 349 | pc.printf("\r\n Calibrating... \r\n"); |
Vigilance88 | 26:fe3a5469dd6b | 350 | dir_motor1=1; //cw |
Vigilance88 | 27:d1814e271a95 | 351 | dir_motor2=0; //cw |
Vigilance88 | 27:d1814e271a95 | 352 | pwm_motor1.write(0.2); //move upper arm slowly cw |
Vigilance88 | 27:d1814e271a95 | 353 | |
Vigilance88 | 26:fe3a5469dd6b | 354 | |
Vigilance88 | 26:fe3a5469dd6b | 355 | while(calibrating){ |
Vigilance88 | 27:d1814e271a95 | 356 | red=0; blue=0; //Debug light is purple during arm calibration |
Vigilance88 | 27:d1814e271a95 | 357 | |
Vigilance88 | 27:d1814e271a95 | 358 | if(done1==true){ |
Vigilance88 | 27:d1814e271a95 | 359 | pwm_motor2.write(0.2); //move forearm slowly cw |
Vigilance88 | 27:d1814e271a95 | 360 | } |
Vigilance88 | 27:d1814e271a95 | 361 | |
Vigilance88 | 26:fe3a5469dd6b | 362 | //when limit switches are hit, stop motor and reset encoder |
Vigilance88 | 26:fe3a5469dd6b | 363 | if(shoulder_limit.read() < 0.5){ //polling |
Vigilance88 | 26:fe3a5469dd6b | 364 | pwm_motor1.write(0); |
Vigilance88 | 26:fe3a5469dd6b | 365 | Encoder1.reset(); |
Vigilance88 | 26:fe3a5469dd6b | 366 | done1 = true; |
Vigilance88 | 27:d1814e271a95 | 367 | pc.printf("Shoulder Limit hit - shutting down motor 1\r\n"); |
Vigilance88 | 26:fe3a5469dd6b | 368 | } |
Vigilance88 | 26:fe3a5469dd6b | 369 | if(elbow_limit.read() < 0.5){ //polling |
Vigilance88 | 26:fe3a5469dd6b | 370 | pwm_motor2.write(0); |
Vigilance88 | 26:fe3a5469dd6b | 371 | Encoder2.reset(); |
Vigilance88 | 26:fe3a5469dd6b | 372 | done2 = true; |
Vigilance88 | 27:d1814e271a95 | 373 | pc.printf("Elbow Limit hit - shutting down motor 2. \r\n"); |
Vigilance88 | 26:fe3a5469dd6b | 374 | } |
Vigilance88 | 26:fe3a5469dd6b | 375 | if(done1 && done2){ |
Vigilance88 | 26:fe3a5469dd6b | 376 | calibrating=false; //Leave while loop when both limits are reached |
Vigilance88 | 26:fe3a5469dd6b | 377 | red=1; blue=1; //Turn debug light off when calibration complete |
Vigilance88 | 26:fe3a5469dd6b | 378 | } |
Vigilance88 | 27:d1814e271a95 | 379 | |
Vigilance88 | 27:d1814e271a95 | 380 | }//end while |
Vigilance88 | 25:49ccdc98639a | 381 | |
Vigilance88 | 27:d1814e271a95 | 382 | //TO DO: |
Vigilance88 | 27:d1814e271a95 | 383 | //mechanical angle limits -> pulses. If 40 degrees -> counts = floor( 40 / (2*pi/4200) ) |
Vigilance88 | 27:d1814e271a95 | 384 | //Encoder1.setPulses(100); //edited QEI library: added setPulses() |
Vigilance88 | 27:d1814e271a95 | 385 | //Encoder2.setPulses(100); //edited QEI library: added setPulses() |
Vigilance88 | 27:d1814e271a95 | 386 | //pc.printf("Elbow Limit hit - shutting down motor 2. Current pulsecount: %i \r\n",Encoder1.getPulses()); |
Vigilance88 | 27:d1814e271a95 | 387 | wait(1); |
Vigilance88 | 27:d1814e271a95 | 388 | pc.printf("Arm Calibration Complete\r\n"); |
Vigilance88 | 26:fe3a5469dd6b | 389 | |
Vigilance88 | 19:0a3ee31dcdb4 | 390 | } |
Vigilance88 | 19:0a3ee31dcdb4 | 391 | |
Vigilance88 | 21:d6a46315d5f5 | 392 | //EMG Maximum Voluntary Contraction measurement |
Vigilance88 | 25:49ccdc98639a | 393 | void emg_mvc() |
Vigilance88 | 25:49ccdc98639a | 394 | { |
Vigilance88 | 24:56db31267f10 | 395 | //double sampletime=0; |
Vigilance88 | 24:56db31267f10 | 396 | //sampletime=+SAMPLE_RATE; |
Vigilance88 | 24:56db31267f10 | 397 | // |
Vigilance88 | 24:56db31267f10 | 398 | // if(sampletime<5) |
Vigilance88 | 25:49ccdc98639a | 399 | //int muscle=1; |
Vigilance88 | 25:49ccdc98639a | 400 | //for(int index=0; index<2500;index++){ //measure 5 seconds@500hz = 2500 samples |
Vigilance88 | 25:49ccdc98639a | 401 | |
Vigilance88 | 24:56db31267f10 | 402 | if(muscle==1){ |
Vigilance88 | 24:56db31267f10 | 403 | |
Vigilance88 | 24:56db31267f10 | 404 | if(biceps_power>bicepsMVC){ |
Vigilance88 | 26:fe3a5469dd6b | 405 | //printf("+ "); |
Vigilance88 | 26:fe3a5469dd6b | 406 | printf("%s+ %s",GREEN_,_GREEN); |
Vigilance88 | 21:d6a46315d5f5 | 407 | bicepsMVC=biceps_power; |
Vigilance88 | 24:56db31267f10 | 408 | } |
Vigilance88 | 25:49ccdc98639a | 409 | else |
Vigilance88 | 25:49ccdc98639a | 410 | printf("- "); |
Vigilance88 | 24:56db31267f10 | 411 | } |
Vigilance88 | 24:56db31267f10 | 412 | |
Vigilance88 | 24:56db31267f10 | 413 | if(muscle==2){ |
Vigilance88 | 24:56db31267f10 | 414 | |
Vigilance88 | 24:56db31267f10 | 415 | if(triceps_power>tricepsMVC){ |
Vigilance88 | 26:fe3a5469dd6b | 416 | printf("%s+ %s",GREEN_,_GREEN); |
Vigilance88 | 24:56db31267f10 | 417 | tricepsMVC=triceps_power; |
Vigilance88 | 24:56db31267f10 | 418 | } |
Vigilance88 | 26:fe3a5469dd6b | 419 | else |
Vigilance88 | 26:fe3a5469dd6b | 420 | printf("- "); |
Vigilance88 | 24:56db31267f10 | 421 | } |
Vigilance88 | 24:56db31267f10 | 422 | |
Vigilance88 | 24:56db31267f10 | 423 | if(muscle==3){ |
Vigilance88 | 24:56db31267f10 | 424 | |
Vigilance88 | 24:56db31267f10 | 425 | if(flexor_power>flexorMVC){ |
Vigilance88 | 26:fe3a5469dd6b | 426 | printf("%s+ %s",GREEN_,_GREEN); |
Vigilance88 | 24:56db31267f10 | 427 | flexorMVC=flexor_power; |
Vigilance88 | 24:56db31267f10 | 428 | } |
Vigilance88 | 26:fe3a5469dd6b | 429 | else |
Vigilance88 | 26:fe3a5469dd6b | 430 | printf("- "); |
Vigilance88 | 24:56db31267f10 | 431 | } |
Vigilance88 | 24:56db31267f10 | 432 | |
Vigilance88 | 24:56db31267f10 | 433 | if(muscle==4){ |
Vigilance88 | 24:56db31267f10 | 434 | |
Vigilance88 | 24:56db31267f10 | 435 | if(extens_power>extensMVC){ |
Vigilance88 | 26:fe3a5469dd6b | 436 | printf("%s+ %s",GREEN_,_GREEN); |
Vigilance88 | 24:56db31267f10 | 437 | extensMVC=extens_power; |
Vigilance88 | 24:56db31267f10 | 438 | } |
Vigilance88 | 26:fe3a5469dd6b | 439 | else |
Vigilance88 | 26:fe3a5469dd6b | 440 | printf("- "); |
Vigilance88 | 24:56db31267f10 | 441 | } |
Vigilance88 | 25:49ccdc98639a | 442 | |
Vigilance88 | 25:49ccdc98639a | 443 | //} |
Vigilance88 | 25:49ccdc98639a | 444 | calibrate_time = calibrate_time + 0.002; |
Vigilance88 | 25:49ccdc98639a | 445 | |
Vigilance88 | 25:49ccdc98639a | 446 | |
Vigilance88 | 25:49ccdc98639a | 447 | |
Vigilance88 | 25:49ccdc98639a | 448 | } |
Vigilance88 | 25:49ccdc98639a | 449 | |
Vigilance88 | 25:49ccdc98639a | 450 | //EMG calibration |
Vigilance88 | 25:49ccdc98639a | 451 | void calibrate_emg() |
Vigilance88 | 25:49ccdc98639a | 452 | { |
Vigilance88 | 25:49ccdc98639a | 453 | Ticker timer; |
Vigilance88 | 25:49ccdc98639a | 454 | |
Vigilance88 | 25:49ccdc98639a | 455 | pc.printf("Testcode calibration \r\n"); |
Vigilance88 | 25:49ccdc98639a | 456 | wait(1); |
Vigilance88 | 25:49ccdc98639a | 457 | pc.printf("+ means current sample is higher than stored MVC\r\n"); |
Vigilance88 | 25:49ccdc98639a | 458 | pc.printf("- means current sample is lower than stored MVC\r\n"); |
Vigilance88 | 26:fe3a5469dd6b | 459 | wait(2); |
Vigilance88 | 25:49ccdc98639a | 460 | pc.printf(" Biceps is first. "); wait(1); |
Vigilance88 | 25:49ccdc98639a | 461 | pc.printf(" Press any key to begin... "); wait(1); |
Vigilance88 | 25:49ccdc98639a | 462 | char input; |
Vigilance88 | 25:49ccdc98639a | 463 | input=pc.getc(); |
Vigilance88 | 25:49ccdc98639a | 464 | pc.putc(input); |
Vigilance88 | 25:49ccdc98639a | 465 | pc.printf(" \r\n Starting in 3... \r\n"); wait(1); |
Vigilance88 | 25:49ccdc98639a | 466 | pc.printf(" \r\n Starting in 2... \r\n"); wait(1); |
Vigilance88 | 25:49ccdc98639a | 467 | pc.printf(" \r\n Starting in 1... \r\n"); wait(1); |
Vigilance88 | 25:49ccdc98639a | 468 | |
Vigilance88 | 25:49ccdc98639a | 469 | start_sampling(); |
Vigilance88 | 25:49ccdc98639a | 470 | muscle=1; |
Vigilance88 | 27:d1814e271a95 | 471 | timer.attach(&emg_mvc,SAMPLE_RATE); |
Vigilance88 | 25:49ccdc98639a | 472 | wait(5); |
Vigilance88 | 25:49ccdc98639a | 473 | timer.detach(); |
Vigilance88 | 26:fe3a5469dd6b | 474 | |
Vigilance88 | 26:fe3a5469dd6b | 475 | pc.printf("\r\n Measurement complete."); wait(1); |
Vigilance88 | 26:fe3a5469dd6b | 476 | pc.printf("\r\n Biceps MVC = %f \r\n",bicepsMVC); wait(1); |
Vigilance88 | 26:fe3a5469dd6b | 477 | pc.printf("Calibrate_emg() exited \r\n"); wait(1); |
Vigilance88 | 26:fe3a5469dd6b | 478 | pc.printf("Measured time: %f seconds \r\n\n",calibrate_time); |
Vigilance88 | 25:49ccdc98639a | 479 | calibrate_time=0; |
Vigilance88 | 25:49ccdc98639a | 480 | |
Vigilance88 | 25:49ccdc98639a | 481 | // Triceps: |
Vigilance88 | 26:fe3a5469dd6b | 482 | muscle=2; |
Vigilance88 | 25:49ccdc98639a | 483 | pc.printf(" Triceps is next "); wait(1); |
Vigilance88 | 25:49ccdc98639a | 484 | pc.printf(" Press any key to begin... "); wait(1); |
Vigilance88 | 25:49ccdc98639a | 485 | input=pc.getc(); |
Vigilance88 | 25:49ccdc98639a | 486 | pc.putc(input); |
Vigilance88 | 25:49ccdc98639a | 487 | pc.printf(" \r\n Starting in 3... \r\n"); wait(1); |
Vigilance88 | 25:49ccdc98639a | 488 | pc.printf(" \r\n Starting in 2... \r\n"); wait(1); |
Vigilance88 | 25:49ccdc98639a | 489 | pc.printf(" \r\n Starting in 1... \r\n"); wait(1); |
Vigilance88 | 25:49ccdc98639a | 490 | start_sampling(); |
Vigilance88 | 25:49ccdc98639a | 491 | muscle=1; |
Vigilance88 | 25:49ccdc98639a | 492 | timer.attach(&emg_mvc,0.002); |
Vigilance88 | 25:49ccdc98639a | 493 | wait(5); |
Vigilance88 | 25:49ccdc98639a | 494 | timer.detach(); |
Vigilance88 | 25:49ccdc98639a | 495 | pc.printf("\r\n Triceps MVC = %f \r\n",tricepsMVC); |
Vigilance88 | 25:49ccdc98639a | 496 | |
Vigilance88 | 25:49ccdc98639a | 497 | pc.printf("Calibrate_emg() exited \r\n"); |
Vigilance88 | 25:49ccdc98639a | 498 | pc.printf("Measured time: %f seconds \r\n",calibrate_time); |
Vigilance88 | 25:49ccdc98639a | 499 | calibrate_time=0; |
Vigilance88 | 25:49ccdc98639a | 500 | |
Vigilance88 | 25:49ccdc98639a | 501 | //Flexor: |
Vigilance88 | 26:fe3a5469dd6b | 502 | muscle=3; |
Vigilance88 | 25:49ccdc98639a | 503 | //Extensor: |
Vigilance88 | 26:fe3a5469dd6b | 504 | muscle=4; |
Vigilance88 | 25:49ccdc98639a | 505 | |
Vigilance88 | 26:fe3a5469dd6b | 506 | //Stop sampling, detach ticker |
Vigilance88 | 25:49ccdc98639a | 507 | stop_sampling(); |
Vigilance88 | 24:56db31267f10 | 508 | |
Vigilance88 | 18:44905b008f44 | 509 | } |
Vigilance88 | 18:44905b008f44 | 510 | |
Vigilance88 | 18:44905b008f44 | 511 | |
Vigilance88 | 18:44905b008f44 | 512 | //Input error and Kp, Kd, Ki, output control signal |
Vigilance88 | 20:0ede3818e08e | 513 | double pid(double error, double kp, double ki, double kd,double &e_int, double &e_prev) |
vsluiter | 2:e314bb3b2d99 | 514 | { |
Vigilance88 | 20:0ede3818e08e | 515 | // Derivative |
Vigilance88 | 24:56db31267f10 | 516 | double e_der = (error-e_prev)/ CONTROL_RATE; |
Vigilance88 | 21:d6a46315d5f5 | 517 | e_der = derfilter.step(e_der); |
Vigilance88 | 21:d6a46315d5f5 | 518 | e_prev = error; |
Vigilance88 | 20:0ede3818e08e | 519 | // Integral |
Vigilance88 | 24:56db31267f10 | 520 | e_int = e_int + CONTROL_RATE * error; |
Vigilance88 | 20:0ede3818e08e | 521 | // PID |
Vigilance88 | 21:d6a46315d5f5 | 522 | return kp*error + ki*e_int + kd * e_der; |
Vigilance88 | 20:0ede3818e08e | 523 | |
Vigilance88 | 18:44905b008f44 | 524 | } |
Vigilance88 | 18:44905b008f44 | 525 | |
Vigilance88 | 20:0ede3818e08e | 526 | //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 | 527 | void control() |
Vigilance88 | 18:44905b008f44 | 528 | { |
Vigilance88 | 20:0ede3818e08e | 529 | //analyze emg (= velocity, averages?) |
Vigilance88 | 18:44905b008f44 | 530 | |
Vigilance88 | 18:44905b008f44 | 531 | //calculate reference position based on the average emg (integrate) |
Vigilance88 | 18:44905b008f44 | 532 | |
Vigilance88 | 27:d1814e271a95 | 533 | //Current position - Encoder counts -> current angle -> Forward Kinematics |
Vigilance88 | 27:d1814e271a95 | 534 | rpc=(2*PI)/ENCODER1_CPR; //radians per count (resolution) - 2pi divided by 4200 |
Vigilance88 | 27:d1814e271a95 | 535 | theta1 = Encoder1.getPulses() * rpc; //multiply resolution with number of counts |
Vigilance88 | 27:d1814e271a95 | 536 | theta2 = Encoder2.getPulses() * rpc; |
Vigilance88 | 27:d1814e271a95 | 537 | current_x = l1 * cos(theta1) + l2 * cos(theta1 + theta2); |
Vigilance88 | 27:d1814e271a95 | 538 | current_y = l1 * sin(theta1) + l2 * sin(theta1 + theta2); |
Vigilance88 | 27:d1814e271a95 | 539 | |
Vigilance88 | 27:d1814e271a95 | 540 | //pc.printf("Calculated current position: x = %f and y = %f \r\n",current_x,current_y); |
Vigilance88 | 27:d1814e271a95 | 541 | |
Vigilance88 | 27:d1814e271a95 | 542 | |
Vigilance88 | 27:d1814e271a95 | 543 | //pc.printf("X is %f and Y is %f \r\n",x,y); |
Vigilance88 | 27:d1814e271a95 | 544 | |
Vigilance88 | 18:44905b008f44 | 545 | //calculate error (refpos-currentpos) currentpos = forward kinematics |
Vigilance88 | 27:d1814e271a95 | 546 | x_error = x - current_x; |
Vigilance88 | 27:d1814e271a95 | 547 | y_error = y - current_y; |
Vigilance88 | 27:d1814e271a95 | 548 | |
Vigilance88 | 27:d1814e271a95 | 549 | //pc.printf("X error is %f and Y error is %f \r\n",x_error,y_error); |
Vigilance88 | 27:d1814e271a95 | 550 | |
Vigilance88 | 27:d1814e271a95 | 551 | //inverse kinematics (refpos to refangle) |
Vigilance88 | 18:44905b008f44 | 552 | |
Vigilance88 | 27:d1814e271a95 | 553 | costheta2 = (pow(x,2) + pow(y,2) - pow(l1,2) - pow(l2,2)) / (2*l1*l2) ; |
Vigilance88 | 27:d1814e271a95 | 554 | sintheta2 = sqrt( 1 - pow(costheta2,2) ); |
Vigilance88 | 27:d1814e271a95 | 555 | |
Vigilance88 | 27:d1814e271a95 | 556 | //pc.printf("costheta2 = %f and sostheta2 = %f \r\n",costheta2,sostheta2); |
Vigilance88 | 27:d1814e271a95 | 557 | |
Vigilance88 | 27:d1814e271a95 | 558 | dtheta2 = atan2(sintheta2,costheta2); |
Vigilance88 | 27:d1814e271a95 | 559 | |
Vigilance88 | 27:d1814e271a95 | 560 | costheta1 = ( x * (l1 + l2 * costheta2) + y * l2 * sintheta2 ) / ( pow(x,2) + pow(y,2) ); |
Vigilance88 | 27:d1814e271a95 | 561 | sintheta1 = sqrt( 1 - pow(costheta1,2) ); |
Vigilance88 | 27:d1814e271a95 | 562 | |
Vigilance88 | 27:d1814e271a95 | 563 | //pc.printf("costheta1 = %f and sostheta1 = %f \r\n",costheta1,sostheta1); |
Vigilance88 | 27:d1814e271a95 | 564 | |
Vigilance88 | 27:d1814e271a95 | 565 | dtheta1 = atan2(sintheta1,costheta1); |
Vigilance88 | 27:d1814e271a95 | 566 | |
Vigilance88 | 27:d1814e271a95 | 567 | |
Vigilance88 | 27:d1814e271a95 | 568 | //Angle error |
Vigilance88 | 27:d1814e271a95 | 569 | |
Vigilance88 | 27:d1814e271a95 | 570 | m1_error = dtheta1-theta1; |
Vigilance88 | 27:d1814e271a95 | 571 | m2_error = dtheta2-theta2; |
Vigilance88 | 27:d1814e271a95 | 572 | |
Vigilance88 | 27:d1814e271a95 | 573 | //pc.printf("m1 error is %f and m2 error is %f \r\n",m1_error,m2_error); |
Vigilance88 | 18:44905b008f44 | 574 | |
Vigilance88 | 18:44905b008f44 | 575 | //PID controller |
Vigilance88 | 24:56db31267f10 | 576 | |
Vigilance88 | 24:56db31267f10 | 577 | u1=pid(m1_error,m1_kp,m1_ki,m1_kd,m1_e_int,m1_e_prev); //motor 1 |
Vigilance88 | 24:56db31267f10 | 578 | u2=pid(m2_error,m2_kp,m2_ki,m2_kd,m2_e_int,m2_e_prev); //motor 2 |
Vigilance88 | 21:d6a46315d5f5 | 579 | |
Vigilance88 | 27:d1814e271a95 | 580 | keep_in_range(&u1,-0.6,0.6); //keep u between -1 and 1, sign = direction, PWM = 0-1 |
Vigilance88 | 27:d1814e271a95 | 581 | keep_in_range(&u2,-0.6,0.6); |
Vigilance88 | 21:d6a46315d5f5 | 582 | |
Vigilance88 | 21:d6a46315d5f5 | 583 | //send PWM and DIR to motor 1 |
Vigilance88 | 21:d6a46315d5f5 | 584 | dir_motor1 = u1>0 ? 1 : 0; //conditional statement dir_motor1 = [condition] ? [if met 1] : [else 0]], same as if else below. |
Vigilance88 | 21:d6a46315d5f5 | 585 | pwm_motor1.write(abs(u1)); |
Vigilance88 | 21:d6a46315d5f5 | 586 | |
Vigilance88 | 21:d6a46315d5f5 | 587 | //send PWM and DIR to motor 2 |
Vigilance88 | 27:d1814e271a95 | 588 | dir_motor2 = u2>0 ? 0 : 1; //conditional statement, same as if else below |
Vigilance88 | 25:49ccdc98639a | 589 | pwm_motor2.write(abs(u2)); |
Vigilance88 | 21:d6a46315d5f5 | 590 | |
Vigilance88 | 21:d6a46315d5f5 | 591 | /*if(u1 > 0) |
Vigilance88 | 21:d6a46315d5f5 | 592 | { |
Vigilance88 | 21:d6a46315d5f5 | 593 | dir_motor1 = 0; |
Vigilance88 | 21:d6a46315d5f5 | 594 | else{ |
Vigilance88 | 21:d6a46315d5f5 | 595 | dir_motor1 = 1; |
Vigilance88 | 21:d6a46315d5f5 | 596 | } |
Vigilance88 | 21:d6a46315d5f5 | 597 | } |
Vigilance88 | 21:d6a46315d5f5 | 598 | pwm_motor1.write(abs(u1)); |
Vigilance88 | 21:d6a46315d5f5 | 599 | |
Vigilance88 | 21:d6a46315d5f5 | 600 | |
Vigilance88 | 21:d6a46315d5f5 | 601 | if(u2 > 0) |
Vigilance88 | 21:d6a46315d5f5 | 602 | { |
Vigilance88 | 21:d6a46315d5f5 | 603 | dir_motor1 = 1; |
Vigilance88 | 21:d6a46315d5f5 | 604 | else{ |
Vigilance88 | 21:d6a46315d5f5 | 605 | dir_motor1 = 0; |
Vigilance88 | 21:d6a46315d5f5 | 606 | } |
Vigilance88 | 21:d6a46315d5f5 | 607 | } |
Vigilance88 | 21:d6a46315d5f5 | 608 | pwm_motor1.write(abs(u2));*/ |
Vigilance88 | 21:d6a46315d5f5 | 609 | |
Vigilance88 | 18:44905b008f44 | 610 | } |
Vigilance88 | 18:44905b008f44 | 611 | |
Vigilance88 | 26:fe3a5469dd6b | 612 | void mainMenu() |
Vigilance88 | 26:fe3a5469dd6b | 613 | { |
Vigilance88 | 26:fe3a5469dd6b | 614 | //Title Box |
Vigilance88 | 26:fe3a5469dd6b | 615 | pc.putc(201); |
Vigilance88 | 26:fe3a5469dd6b | 616 | for(int j=0;j<33;j++){ |
Vigilance88 | 26:fe3a5469dd6b | 617 | pc.putc(205); |
Vigilance88 | 26:fe3a5469dd6b | 618 | } |
Vigilance88 | 26:fe3a5469dd6b | 619 | pc.putc(187); |
Vigilance88 | 26:fe3a5469dd6b | 620 | pc.printf("\n\r"); |
Vigilance88 | 26:fe3a5469dd6b | 621 | pc.putc(186); pc.printf(" BioRobotics M9 - Group 14 "); pc.putc(186); |
Vigilance88 | 26:fe3a5469dd6b | 622 | pc.printf("\n\r"); |
Vigilance88 | 26:fe3a5469dd6b | 623 | pc.putc(186); pc.printf(" Robot powered ON "); pc.putc(186); |
Vigilance88 | 26:fe3a5469dd6b | 624 | pc.printf("\n\r"); |
Vigilance88 | 26:fe3a5469dd6b | 625 | pc.putc(200); |
Vigilance88 | 26:fe3a5469dd6b | 626 | for(int k=0;k<33;k++){ |
Vigilance88 | 26:fe3a5469dd6b | 627 | pc.putc(205); |
Vigilance88 | 26:fe3a5469dd6b | 628 | } |
Vigilance88 | 26:fe3a5469dd6b | 629 | pc.putc(188); |
Vigilance88 | 26:fe3a5469dd6b | 630 | |
Vigilance88 | 26:fe3a5469dd6b | 631 | pc.printf("\n\r"); |
Vigilance88 | 26:fe3a5469dd6b | 632 | //endbox |
Vigilance88 | 26:fe3a5469dd6b | 633 | } |
Vigilance88 | 24:56db31267f10 | 634 | void caliMenu(){}; |
Vigilance88 | 24:56db31267f10 | 635 | |
Vigilance88 | 24:56db31267f10 | 636 | //Start sampling |
Vigilance88 | 24:56db31267f10 | 637 | void start_sampling(void) |
Vigilance88 | 24:56db31267f10 | 638 | { |
Vigilance88 | 24:56db31267f10 | 639 | sample_timer.attach(&sample_filter,SAMPLE_RATE); //500 Hz EMG |
Vigilance88 | 26:fe3a5469dd6b | 640 | |
Vigilance88 | 26:fe3a5469dd6b | 641 | //Debug LED will be green when sampling is active |
Vigilance88 | 26:fe3a5469dd6b | 642 | green=0; |
Vigilance88 | 25:49ccdc98639a | 643 | pc.printf("||- started sampling -|| \r\n"); |
Vigilance88 | 24:56db31267f10 | 644 | } |
Vigilance88 | 24:56db31267f10 | 645 | |
Vigilance88 | 24:56db31267f10 | 646 | //stop sampling |
Vigilance88 | 24:56db31267f10 | 647 | void stop_sampling(void) |
Vigilance88 | 24:56db31267f10 | 648 | { |
Vigilance88 | 24:56db31267f10 | 649 | sample_timer.detach(); |
Vigilance88 | 26:fe3a5469dd6b | 650 | |
Vigilance88 | 26:fe3a5469dd6b | 651 | //Debug LED will be turned off when sampling stops |
Vigilance88 | 26:fe3a5469dd6b | 652 | green=1; |
Vigilance88 | 25:49ccdc98639a | 653 | pc.printf("||- stopped sampling -|| \r\n"); |
Vigilance88 | 24:56db31267f10 | 654 | } |
Vigilance88 | 24:56db31267f10 | 655 | |
Vigilance88 | 18:44905b008f44 | 656 | //Start control |
Vigilance88 | 18:44905b008f44 | 657 | void start_control(void) |
Vigilance88 | 18:44905b008f44 | 658 | { |
Vigilance88 | 27:d1814e271a95 | 659 | control_timer.attach(&control,CONTROL_RATE); //100 Hz control |
Vigilance88 | 26:fe3a5469dd6b | 660 | |
Vigilance88 | 26:fe3a5469dd6b | 661 | //Debug LED will be blue when control is on. If sampling and control are on -> blue + green = cyan. |
Vigilance88 | 26:fe3a5469dd6b | 662 | blue=0; |
Vigilance88 | 26:fe3a5469dd6b | 663 | pc.printf("||- started control -|| \r\n"); |
Vigilance88 | 18:44905b008f44 | 664 | } |
Vigilance88 | 18:44905b008f44 | 665 | |
Vigilance88 | 18:44905b008f44 | 666 | //stop control |
Vigilance88 | 18:44905b008f44 | 667 | void stop_control(void) |
Vigilance88 | 18:44905b008f44 | 668 | { |
Vigilance88 | 18:44905b008f44 | 669 | control_timer.detach(); |
Vigilance88 | 26:fe3a5469dd6b | 670 | |
Vigilance88 | 26:fe3a5469dd6b | 671 | //Debug LED will be off when control is off |
Vigilance88 | 26:fe3a5469dd6b | 672 | blue=1; |
Vigilance88 | 26:fe3a5469dd6b | 673 | pc.printf("||- stopped control -|| \r\n"); |
vsluiter | 2:e314bb3b2d99 | 674 | } |
vsluiter | 0:32bb76391d89 | 675 | |
Vigilance88 | 21:d6a46315d5f5 | 676 | |
Vigilance88 | 21:d6a46315d5f5 | 677 | void calibrate() |
vsluiter | 0:32bb76391d89 | 678 | { |
Vigilance88 | 21:d6a46315d5f5 | 679 | |
Vigilance88 | 21:d6a46315d5f5 | 680 | } |
tomlankhorst | 15:0da764eea774 | 681 | |
Vigilance88 | 26:fe3a5469dd6b | 682 | //Clears the putty (or other terminal) window |
Vigilance88 | 26:fe3a5469dd6b | 683 | void clearTerminal() |
Vigilance88 | 26:fe3a5469dd6b | 684 | { |
Vigilance88 | 26:fe3a5469dd6b | 685 | pc.putc(27); |
Vigilance88 | 26:fe3a5469dd6b | 686 | pc.printf("[2J"); // clear screen |
Vigilance88 | 26:fe3a5469dd6b | 687 | pc.putc(27); // ESC |
Vigilance88 | 26:fe3a5469dd6b | 688 | pc.printf("[H"); // cursor to home |
Vigilance88 | 26:fe3a5469dd6b | 689 | } |
Vigilance88 | 21:d6a46315d5f5 | 690 | |
Vigilance88 | 21:d6a46315d5f5 | 691 | //keeps input limited between min max |
Vigilance88 | 24:56db31267f10 | 692 | void keep_in_range(double * in, double min, double max) |
Vigilance88 | 18:44905b008f44 | 693 | { |
Vigilance88 | 18:44905b008f44 | 694 | *in > min ? *in < max? : *in = max: *in = min; |
vsluiter | 0:32bb76391d89 | 695 | } |