2nd draft
Dependencies: HIDScope MODSERIAL QEI biquadFilter mbed Servo
Fork of robot_mockup by
main.cpp@32:76c4d7bb2022, 2015-10-22 (annotated)
- Committer:
- Vigilance88
- Date:
- Thu Oct 22 10:57:50 2015 +0000
- Revision:
- 32:76c4d7bb2022
- Parent:
- 31:7b8b8459bddc
- Child:
- 33:daa6ec305441
started on DLS control code
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 | 28:743485bb51e4 | 56 | InterruptIn shoulder_limit(D2); //using FRDM buttons |
Vigilance88 | 28:743485bb51e4 | 57 | InterruptIn elbow_limit(D3); //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 | 29:948b0b14f6be | 98 | const double m1_kp=0.001; const double m1_ki=0.0125; const double m1_kd=0.1; //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 | 29:948b0b14f6be | 101 | const double m2_kp=0.001; const double m2_ki=0.0125; const double m2_kd=0.1; //Proportional, integral and derivative gains. |
Vigilance88 | 24:56db31267f10 | 102 | |
Vigilance88 | 32:76c4d7bb2022 | 103 | //Calibration, checks if elbow/shoulder are done |
Vigilance88 | 32:76c4d7bb2022 | 104 | bool done1 = false; |
Vigilance88 | 32:76c4d7bb2022 | 105 | bool done2 = false; |
Vigilance88 | 32:76c4d7bb2022 | 106 | |
Vigilance88 | 24:56db31267f10 | 107 | //highpass filter 20 Hz |
Vigilance88 | 24:56db31267f10 | 108 | const double high_b0 = 0.956543225556877; |
Vigilance88 | 24:56db31267f10 | 109 | const double high_b1 = -1.91308645113754; |
Vigilance88 | 24:56db31267f10 | 110 | const double high_b2 = 0.956543225556877; |
Vigilance88 | 24:56db31267f10 | 111 | const double high_a1 = -1.91197067426073; |
Vigilance88 | 24:56db31267f10 | 112 | const double high_a2 = 0.9149758348014341; |
Vigilance88 | 24:56db31267f10 | 113 | |
Vigilance88 | 24:56db31267f10 | 114 | //notchfilter 50Hz |
Vigilance88 | 24:56db31267f10 | 115 | /* ** Primary Filter (H1)** |
Vigilance88 | 24:56db31267f10 | 116 | Filter Arithmetic = Floating Point (Double Precision) |
Vigilance88 | 24:56db31267f10 | 117 | Architecture = IIR |
Vigilance88 | 24:56db31267f10 | 118 | Response = Bandstop |
Vigilance88 | 24:56db31267f10 | 119 | Method = Butterworth |
Vigilance88 | 24:56db31267f10 | 120 | Biquad = Yes |
Vigilance88 | 24:56db31267f10 | 121 | Stable = Yes |
Vigilance88 | 24:56db31267f10 | 122 | Sampling Frequency = 500Hz |
Vigilance88 | 24:56db31267f10 | 123 | Filter Order = 2 |
Vigilance88 | 24:56db31267f10 | 124 | |
Vigilance88 | 24:56db31267f10 | 125 | Band Frequencies (Hz) Att/Ripple (dB) Biquad #1 Biquad #2 |
Vigilance88 | 24:56db31267f10 | 126 | |
Vigilance88 | 24:56db31267f10 | 127 | 1 0, 48 0.001 Gain = 1.000000 Gain = 0.973674 |
Vigilance88 | 24:56db31267f10 | 128 | 2 49, 51 -60.000 B = [ 1.00000000000, -1.61816176147, 1.00000000000] B = [ 1.00000000000, -1.61816176147, 1.00000000000] |
Vigilance88 | 24:56db31267f10 | 129 | 3 52, 250 0.001 A = [ 1.00000000000, -1.58071559235, 0.97319685401] A = [ 1.00000000000, -1.61244708381, 0.97415116257] |
Vigilance88 | 24:56db31267f10 | 130 | */ |
Vigilance88 | 24:56db31267f10 | 131 | |
Vigilance88 | 24:56db31267f10 | 132 | //biquad 1 |
Vigilance88 | 24:56db31267f10 | 133 | const double notch1gain = 1.000000; |
Vigilance88 | 24:56db31267f10 | 134 | const double notch1_b0 = 1; |
Vigilance88 | 24:56db31267f10 | 135 | const double notch1_b1 = -1.61816176147 * notch1gain; |
Vigilance88 | 24:56db31267f10 | 136 | const double notch1_b2 = 1.00000000000 * notch1gain; |
Vigilance88 | 24:56db31267f10 | 137 | const double notch1_a1 = -1.58071559235 * notch1gain; |
Vigilance88 | 24:56db31267f10 | 138 | const double notch1_a2 = 0.97319685401 * notch1gain; |
Vigilance88 | 24:56db31267f10 | 139 | |
Vigilance88 | 24:56db31267f10 | 140 | //biquad 2 |
Vigilance88 | 24:56db31267f10 | 141 | const double notch2gain = 0.973674; |
Vigilance88 | 24:56db31267f10 | 142 | const double notch2_b0 = 1 * notch2gain; |
Vigilance88 | 24:56db31267f10 | 143 | const double notch2_b1 = -1.61816176147 * notch2gain; |
Vigilance88 | 24:56db31267f10 | 144 | const double notch2_b2 = 1.00000000000 * notch2gain; |
Vigilance88 | 24:56db31267f10 | 145 | const double notch2_a1 = -1.61244708381 * notch2gain; |
Vigilance88 | 24:56db31267f10 | 146 | const double notch2_a2 = 0.97415116257 * notch2gain; |
Vigilance88 | 24:56db31267f10 | 147 | |
Vigilance88 | 26:fe3a5469dd6b | 148 | //lowpass filter 7 Hz - envelope |
Vigilance88 | 24:56db31267f10 | 149 | const double low_b0 = 0.000119046743110057; |
Vigilance88 | 24:56db31267f10 | 150 | const double low_b1 = 0.000238093486220118; |
Vigilance88 | 24:56db31267f10 | 151 | const double low_b2 = 0.000119046743110057; |
Vigilance88 | 24:56db31267f10 | 152 | const double low_a1 = -1.968902268531908; |
Vigilance88 | 24:56db31267f10 | 153 | const double low_a2 = 0.9693784555043481; |
Vigilance88 | 21:d6a46315d5f5 | 154 | |
Vigilance88 | 29:948b0b14f6be | 155 | //Forward and Inverse Kinematics |
Vigilance88 | 28:743485bb51e4 | 156 | const double l1 = 0.25; const double l2 = 0.25; |
Vigilance88 | 28:743485bb51e4 | 157 | double current_x; double current_y; |
Vigilance88 | 28:743485bb51e4 | 158 | double theta1; double theta2; |
Vigilance88 | 28:743485bb51e4 | 159 | double dtheta1; double dtheta2; |
Vigilance88 | 28:743485bb51e4 | 160 | double rpc; |
Vigilance88 | 28:743485bb51e4 | 161 | double x; double y; |
Vigilance88 | 28:743485bb51e4 | 162 | double x_error; double y_error; |
Vigilance88 | 28:743485bb51e4 | 163 | double costheta1; double sintheta1; |
Vigilance88 | 28:743485bb51e4 | 164 | double costheta2; double sintheta2; |
Vigilance88 | 32:76c4d7bb2022 | 165 | double dls1, dls2, dls3, dls4; |
Vigilance88 | 32:76c4d7bb2022 | 166 | double q1_error, q2_error; |
Vigilance88 | 32:76c4d7bb2022 | 167 | double lambda=0.1; |
Vigilance88 | 21:d6a46315d5f5 | 168 | |
Vigilance88 | 21:d6a46315d5f5 | 169 | /*-------------------------------------------------------------------------------------------------------------------- |
Vigilance88 | 24:56db31267f10 | 170 | ---- Filters --------------------------------------------------------------------------------------------------------- |
Vigilance88 | 21:d6a46315d5f5 | 171 | --------------------------------------------------------------------------------------------------------------------*/ |
Vigilance88 | 24:56db31267f10 | 172 | |
Vigilance88 | 24:56db31267f10 | 173 | //Using biquadFilter library |
Vigilance88 | 24:56db31267f10 | 174 | //Syntax: biquadFilter filter(a1, a2, b0, b1, b2); coefficients. Call with: filter.step(u), with u signal to be filtered. |
Vigilance88 | 26:fe3a5469dd6b | 175 | //Biceps |
Vigilance88 | 24:56db31267f10 | 176 | biquadFilter highpass( high_a1 , high_a2 , high_b0 , high_b1 , high_b2 ); // removes DC and movement artefacts |
Vigilance88 | 24:56db31267f10 | 177 | biquadFilter notch1( notch1_a1 , notch1_a2 , notch1_b0 , notch1_b1 , notch1_b2 ); // removes 49-51 Hz power interference |
Vigilance88 | 24:56db31267f10 | 178 | biquadFilter notch2( notch2_a1 , notch2_a2 , notch2_b0 , notch2_b1 , notch2_b2 ); // |
Vigilance88 | 24:56db31267f10 | 179 | biquadFilter lowpass( low_a1 , low_a2 , low_b0 , low_b1 , low_b2 ); // EMG envelope |
Vigilance88 | 25:49ccdc98639a | 180 | |
Vigilance88 | 26:fe3a5469dd6b | 181 | //Triceps |
Vigilance88 | 25:49ccdc98639a | 182 | biquadFilter highpass2( high_a1 , high_a2 , high_b0 , high_b1 , high_b2 ); // removes DC and movement artefacts |
Vigilance88 | 26:fe3a5469dd6b | 183 | biquadFilter notch1_2( notch1_a1 , notch1_a2 , notch1_b0 , notch1_b1 , notch1_b2 ); // removes 49-51 Hz power interference |
Vigilance88 | 26:fe3a5469dd6b | 184 | biquadFilter notch2_2( notch2_a1 , notch2_a2 , notch2_b0 , notch2_b1 , notch2_b2 ); // |
Vigilance88 | 25:49ccdc98639a | 185 | biquadFilter lowpass2( low_a1 , low_a2 , low_b0 , low_b1 , low_b2 ); // EMG envelope |
Vigilance88 | 25:49ccdc98639a | 186 | |
Vigilance88 | 26:fe3a5469dd6b | 187 | //Flexor |
Vigilance88 | 25:49ccdc98639a | 188 | biquadFilter highpass3( high_a1 , high_a2 , high_b0 , high_b1 , high_b2 ); // removes DC and movement artefacts |
Vigilance88 | 26:fe3a5469dd6b | 189 | biquadFilter notch1_3( notch1_a1 , notch1_a2 , notch1_b0 , notch1_b1 , notch1_b2 ); // removes 49-51 Hz power interference |
Vigilance88 | 26:fe3a5469dd6b | 190 | biquadFilter notch2_3( notch2_a1 , notch2_a2 , notch2_b0 , notch2_b1 , notch2_b2 ); // |
Vigilance88 | 25:49ccdc98639a | 191 | biquadFilter lowpass3( low_a1 , low_a2 , low_b0 , low_b1 , low_b2 ); // EMG envelope |
Vigilance88 | 25:49ccdc98639a | 192 | |
Vigilance88 | 26:fe3a5469dd6b | 193 | //Extensor |
Vigilance88 | 25:49ccdc98639a | 194 | biquadFilter highpass4( high_a1 , high_a2 , high_b0 , high_b1 , high_b2 ); // removes DC and movement artefacts |
Vigilance88 | 26:fe3a5469dd6b | 195 | biquadFilter notch1_4( notch1_a1 , notch1_a2 , notch1_b0 , notch1_b1 , notch1_b2 ); // removes 49-51 Hz power interference |
Vigilance88 | 26:fe3a5469dd6b | 196 | biquadFilter notch2_4( notch2_a1 , notch2_a2 , notch2_b0 , notch2_b1 , notch2_b2 ); // |
Vigilance88 | 25:49ccdc98639a | 197 | biquadFilter lowpass4( low_a1 , low_a2 , low_b0 , low_b1 , low_b2 ); // EMG envelope |
Vigilance88 | 25:49ccdc98639a | 198 | |
Vigilance88 | 26:fe3a5469dd6b | 199 | //PID filter (lowpass ??? Hz) |
Vigilance88 | 29:948b0b14f6be | 200 | biquadFilter derfilter( low_a1 , low_a2 , low_b0 , low_b1 , low_b2 ); // derivative filter |
Vigilance88 | 24:56db31267f10 | 201 | |
Vigilance88 | 24:56db31267f10 | 202 | /*-------------------------------------------------------------------------------------------------------------------- |
Vigilance88 | 24:56db31267f10 | 203 | ---- DECLARE FUNCTION NAMES ------------------------------------------------------------------------------------------ |
Vigilance88 | 24:56db31267f10 | 204 | --------------------------------------------------------------------------------------------------------------------*/ |
Vigilance88 | 26:fe3a5469dd6b | 205 | |
Vigilance88 | 26:fe3a5469dd6b | 206 | void sample_filter(void); //Sampling and filtering |
Vigilance88 | 26:fe3a5469dd6b | 207 | void control(); //Control - reference -> error -> pid -> motor output |
Vigilance88 | 32:76c4d7bb2022 | 208 | void dlscontrol(); |
Vigilance88 | 26:fe3a5469dd6b | 209 | void calibrate_emg(); //Instructions + measurement of MVC of each muscle |
Vigilance88 | 26:fe3a5469dd6b | 210 | void emg_mvc(); //Helper funcion for storing MVC value |
Vigilance88 | 26:fe3a5469dd6b | 211 | void calibrate_arm(void); //Calibration of the arm with limit switches |
Vigilance88 | 26:fe3a5469dd6b | 212 | void start_sampling(void); //Attaches the sample_filter function to a 500Hz ticker |
Vigilance88 | 26:fe3a5469dd6b | 213 | void stop_sampling(void); //Stops sample_filter |
Vigilance88 | 26:fe3a5469dd6b | 214 | void start_control(void); //Attaches the control function to a 100Hz ticker |
Vigilance88 | 26:fe3a5469dd6b | 215 | void stop_control(void); //Stops control function |
Vigilance88 | 26:fe3a5469dd6b | 216 | |
Vigilance88 | 26:fe3a5469dd6b | 217 | //Keeps the input between min and max value |
Vigilance88 | 24:56db31267f10 | 218 | void keep_in_range(double * in, double min, double max); |
Vigilance88 | 26:fe3a5469dd6b | 219 | |
Vigilance88 | 26:fe3a5469dd6b | 220 | //Reusable PID controller, previous and integral error need to be passed by reference |
Vigilance88 | 21:d6a46315d5f5 | 221 | double pid(double error, double kp, double ki, double kd,double &e_int, double &e_prev); |
Vigilance88 | 18:44905b008f44 | 222 | |
Vigilance88 | 26:fe3a5469dd6b | 223 | //Menu functions |
Vigilance88 | 21:d6a46315d5f5 | 224 | void mainMenu(); |
Vigilance88 | 21:d6a46315d5f5 | 225 | void caliMenu(); |
Vigilance88 | 28:743485bb51e4 | 226 | void controlMenu(); |
Vigilance88 | 29:948b0b14f6be | 227 | void controlButtons(); |
Vigilance88 | 26:fe3a5469dd6b | 228 | void clearTerminal(); |
Vigilance88 | 28:743485bb51e4 | 229 | void emgInstructions(); |
Vigilance88 | 28:743485bb51e4 | 230 | void titleBox(); |
Vigilance88 | 26:fe3a5469dd6b | 231 | |
Vigilance88 | 32:76c4d7bb2022 | 232 | //Limit switches - power off motors if switches hit (rising edge interrupt) |
Vigilance88 | 32:76c4d7bb2022 | 233 | void shoulder(); |
Vigilance88 | 32:76c4d7bb2022 | 234 | void elbow(); |
Vigilance88 | 21:d6a46315d5f5 | 235 | |
Vigilance88 | 21:d6a46315d5f5 | 236 | /*-------------------------------------------------------------------------------------------------------------------- |
Vigilance88 | 21:d6a46315d5f5 | 237 | ---- MAIN LOOP ------------------------------------------------------------------------------------------------------- |
Vigilance88 | 21:d6a46315d5f5 | 238 | --------------------------------------------------------------------------------------------------------------------*/ |
Vigilance88 | 21:d6a46315d5f5 | 239 | |
Vigilance88 | 21:d6a46315d5f5 | 240 | int main() |
Vigilance88 | 21:d6a46315d5f5 | 241 | { |
Vigilance88 | 29:948b0b14f6be | 242 | pc.baud(115200); //serial baudrate |
Vigilance88 | 30:a9fdd3202ca2 | 243 | red=1; green=1; blue=1; //Make sure debug LEDs are off |
Vigilance88 | 26:fe3a5469dd6b | 244 | |
Vigilance88 | 26:fe3a5469dd6b | 245 | //Set PwmOut frequency to 10k Hz |
Vigilance88 | 28:743485bb51e4 | 246 | //pwm_motor1.period(PWM_PERIOD); |
Vigilance88 | 28:743485bb51e4 | 247 | //pwm_motor2.period(PWM_PERIOD); |
Vigilance88 | 26:fe3a5469dd6b | 248 | |
Vigilance88 | 26:fe3a5469dd6b | 249 | clearTerminal(); //Clear the putty window |
Vigilance88 | 26:fe3a5469dd6b | 250 | |
Vigilance88 | 24:56db31267f10 | 251 | // make a menu, user has to initiate next step |
Vigilance88 | 28:743485bb51e4 | 252 | titleBox(); |
Vigilance88 | 26:fe3a5469dd6b | 253 | mainMenu(); |
Vigilance88 | 25:49ccdc98639a | 254 | //caliMenu(); // Menu function |
Vigilance88 | 25:49ccdc98639a | 255 | //calibrate_arm(); //Start Calibration |
Vigilance88 | 25:49ccdc98639a | 256 | |
Vigilance88 | 27:d1814e271a95 | 257 | //calibrate_emg(); |
Vigilance88 | 28:743485bb51e4 | 258 | |
Vigilance88 | 30:a9fdd3202ca2 | 259 | //set initial reference position |
Vigilance88 | 30:a9fdd3202ca2 | 260 | x=0.5; y=0; |
Vigilance88 | 28:743485bb51e4 | 261 | |
Vigilance88 | 28:743485bb51e4 | 262 | //start_control(); //100 Hz control |
Vigilance88 | 21:d6a46315d5f5 | 263 | |
Vigilance88 | 21:d6a46315d5f5 | 264 | //maybe some stop commands when a button is pressed: detach from timers. |
Vigilance88 | 21:d6a46315d5f5 | 265 | //stop_control(); |
Vigilance88 | 29:948b0b14f6be | 266 | start_sampling(); |
Vigilance88 | 32:76c4d7bb2022 | 267 | |
Vigilance88 | 28:743485bb51e4 | 268 | //char c; |
Vigilance88 | 28:743485bb51e4 | 269 | |
Vigilance88 | 28:743485bb51e4 | 270 | |
Vigilance88 | 28:743485bb51e4 | 271 | |
Vigilance88 | 32:76c4d7bb2022 | 272 | char command=0; |
Vigilance88 | 27:d1814e271a95 | 273 | |
Vigilance88 | 28:743485bb51e4 | 274 | while(command != 'Q' && command != 'q') |
Vigilance88 | 28:743485bb51e4 | 275 | { |
Vigilance88 | 28:743485bb51e4 | 276 | if(pc.readable()){ |
Vigilance88 | 28:743485bb51e4 | 277 | command = pc.getc(); |
Vigilance88 | 28:743485bb51e4 | 278 | |
Vigilance88 | 28:743485bb51e4 | 279 | switch(command){ |
Vigilance88 | 28:743485bb51e4 | 280 | |
Vigilance88 | 28:743485bb51e4 | 281 | case 'c': |
Vigilance88 | 28:743485bb51e4 | 282 | case 'C': |
Vigilance88 | 28:743485bb51e4 | 283 | pc.printf("\n\r => You chose calibration.\r\n\n"); |
Vigilance88 | 28:743485bb51e4 | 284 | caliMenu(); |
Vigilance88 | 28:743485bb51e4 | 285 | |
Vigilance88 | 28:743485bb51e4 | 286 | char command2=0; |
Vigilance88 | 28:743485bb51e4 | 287 | |
Vigilance88 | 28:743485bb51e4 | 288 | while(command2 != 'B' && command2 != 'b'){ |
Vigilance88 | 28:743485bb51e4 | 289 | command2 = pc.getc(); |
Vigilance88 | 28:743485bb51e4 | 290 | switch(command2){ |
Vigilance88 | 28:743485bb51e4 | 291 | case 'a': |
Vigilance88 | 28:743485bb51e4 | 292 | case 'A': |
Vigilance88 | 28:743485bb51e4 | 293 | pc.printf("\n\r => Arm Calibration Starting... please wait \n\r"); |
Vigilance88 | 28:743485bb51e4 | 294 | calibrate_arm(); |
Vigilance88 | 28:743485bb51e4 | 295 | wait(1); |
Vigilance88 | 28:743485bb51e4 | 296 | caliMenu(); |
Vigilance88 | 28:743485bb51e4 | 297 | break; |
Vigilance88 | 28:743485bb51e4 | 298 | |
Vigilance88 | 28:743485bb51e4 | 299 | case 'e': |
Vigilance88 | 28:743485bb51e4 | 300 | case 'E': |
Vigilance88 | 28:743485bb51e4 | 301 | pc.printf("\n\r => EMG Calibration Starting... please wait \n\r"); |
Vigilance88 | 28:743485bb51e4 | 302 | wait(1); |
Vigilance88 | 28:743485bb51e4 | 303 | emgInstructions(); |
Vigilance88 | 28:743485bb51e4 | 304 | calibrate_emg(); |
Vigilance88 | 32:76c4d7bb2022 | 305 | pc.printf("\n\r------------------------- \n\r"); |
Vigilance88 | 28:743485bb51e4 | 306 | pc.printf("\n\r EMG Calibration complete \n\r"); |
Vigilance88 | 32:76c4d7bb2022 | 307 | pc.printf("\n\r------------------------- \n\r"); |
Vigilance88 | 28:743485bb51e4 | 308 | caliMenu(); |
Vigilance88 | 28:743485bb51e4 | 309 | break; |
Vigilance88 | 28:743485bb51e4 | 310 | |
Vigilance88 | 28:743485bb51e4 | 311 | case 'b': |
Vigilance88 | 28:743485bb51e4 | 312 | case 'B': |
Vigilance88 | 28:743485bb51e4 | 313 | pc.printf("\n\r => Going back to main menu.. \n\r"); |
Vigilance88 | 28:743485bb51e4 | 314 | mainMenu(); |
Vigilance88 | 28:743485bb51e4 | 315 | break; |
Vigilance88 | 28:743485bb51e4 | 316 | }//end switch |
Vigilance88 | 28:743485bb51e4 | 317 | |
Vigilance88 | 28:743485bb51e4 | 318 | }//end while |
Vigilance88 | 28:743485bb51e4 | 319 | break; |
Vigilance88 | 28:743485bb51e4 | 320 | case 's': |
Vigilance88 | 28:743485bb51e4 | 321 | case 'S': |
Vigilance88 | 28:743485bb51e4 | 322 | pc.printf("=> You chose control \r\n\n"); |
Vigilance88 | 28:743485bb51e4 | 323 | wait(1); |
Vigilance88 | 28:743485bb51e4 | 324 | start_sampling(); |
Vigilance88 | 28:743485bb51e4 | 325 | wait(1); |
Vigilance88 | 28:743485bb51e4 | 326 | start_control(); |
Vigilance88 | 28:743485bb51e4 | 327 | wait(1); |
Vigilance88 | 29:948b0b14f6be | 328 | controlButtons(); |
Vigilance88 | 28:743485bb51e4 | 329 | break; |
Vigilance88 | 28:743485bb51e4 | 330 | case 'R': |
Vigilance88 | 28:743485bb51e4 | 331 | red=!red; |
Vigilance88 | 28:743485bb51e4 | 332 | pc.printf("=> Red LED triggered \n\r"); |
Vigilance88 | 28:743485bb51e4 | 333 | break; |
Vigilance88 | 28:743485bb51e4 | 334 | case 'G': |
Vigilance88 | 28:743485bb51e4 | 335 | green=!green; |
Vigilance88 | 28:743485bb51e4 | 336 | pc.printf("=> Green LED triggered \n\r"); |
Vigilance88 | 28:743485bb51e4 | 337 | break; |
Vigilance88 | 28:743485bb51e4 | 338 | case 'B': |
Vigilance88 | 28:743485bb51e4 | 339 | blue=!blue; |
Vigilance88 | 28:743485bb51e4 | 340 | pc.printf("=> Blue LED triggered \n\r"); |
Vigilance88 | 28:743485bb51e4 | 341 | break; |
Vigilance88 | 28:743485bb51e4 | 342 | case 'q': |
Vigilance88 | 28:743485bb51e4 | 343 | case 'Q': |
Vigilance88 | 28:743485bb51e4 | 344 | |
Vigilance88 | 28:743485bb51e4 | 345 | break; |
Vigilance88 | 28:743485bb51e4 | 346 | default: |
Vigilance88 | 28:743485bb51e4 | 347 | pc.printf("=> Invalid Input \n\r"); |
Vigilance88 | 28:743485bb51e4 | 348 | break; |
Vigilance88 | 28:743485bb51e4 | 349 | } //end switch |
Vigilance88 | 28:743485bb51e4 | 350 | } // end if pc readable |
Vigilance88 | 28:743485bb51e4 | 351 | |
Vigilance88 | 28:743485bb51e4 | 352 | } // end while loop |
Vigilance88 | 28:743485bb51e4 | 353 | |
Vigilance88 | 28:743485bb51e4 | 354 | |
Vigilance88 | 28:743485bb51e4 | 355 | |
Vigilance88 | 28:743485bb51e4 | 356 | //When end of while loop reached (user chose quit program) - detach all timers and stop motors. |
Vigilance88 | 28:743485bb51e4 | 357 | |
Vigilance88 | 28:743485bb51e4 | 358 | pc.printf("\r\n------------------------------ \n\r"); |
Vigilance88 | 28:743485bb51e4 | 359 | pc.printf("Program Offline \n\r"); |
Vigilance88 | 28:743485bb51e4 | 360 | pc.printf("Reset to start\r\n"); |
Vigilance88 | 28:743485bb51e4 | 361 | pc.printf("------------------------------ \n\r"); |
Vigilance88 | 28:743485bb51e4 | 362 | } |
Vigilance88 | 28:743485bb51e4 | 363 | //end of main |
Vigilance88 | 28:743485bb51e4 | 364 | |
Vigilance88 | 28:743485bb51e4 | 365 | /*-------------------------------------------------------------------------------------------------------------------- |
Vigilance88 | 28:743485bb51e4 | 366 | ---- FUNCTIONS ------------------------------------------------------------------------------------------------------- |
Vigilance88 | 28:743485bb51e4 | 367 | --------------------------------------------------------------------------------------------------------------------*/ |
Vigilance88 | 28:743485bb51e4 | 368 | |
Vigilance88 | 29:948b0b14f6be | 369 | void controlButtons() |
Vigilance88 | 28:743485bb51e4 | 370 | { |
Vigilance88 | 28:743485bb51e4 | 371 | controlMenu(); |
Vigilance88 | 28:743485bb51e4 | 372 | char c=0; |
Vigilance88 | 28:743485bb51e4 | 373 | while(c != 'Q' && c != 'q') { |
Vigilance88 | 27:d1814e271a95 | 374 | |
Vigilance88 | 27:d1814e271a95 | 375 | if( pc.readable() ){ |
Vigilance88 | 27:d1814e271a95 | 376 | c = pc.getc(); |
Vigilance88 | 27:d1814e271a95 | 377 | switch (c) |
Vigilance88 | 27:d1814e271a95 | 378 | { |
Vigilance88 | 27:d1814e271a95 | 379 | case '1' : |
Vigilance88 | 27:d1814e271a95 | 380 | x = x + 0.01; |
Vigilance88 | 32:76c4d7bb2022 | 381 | |
Vigilance88 | 27:d1814e271a95 | 382 | break; |
Vigilance88 | 27:d1814e271a95 | 383 | |
Vigilance88 | 27:d1814e271a95 | 384 | case '2' : |
Vigilance88 | 27:d1814e271a95 | 385 | x-=0.01; |
Vigilance88 | 32:76c4d7bb2022 | 386 | |
Vigilance88 | 27:d1814e271a95 | 387 | break; |
Vigilance88 | 27:d1814e271a95 | 388 | |
Vigilance88 | 27:d1814e271a95 | 389 | case '3' : |
Vigilance88 | 27:d1814e271a95 | 390 | y+=0.01; |
Vigilance88 | 32:76c4d7bb2022 | 391 | |
Vigilance88 | 27:d1814e271a95 | 392 | break; |
Vigilance88 | 27:d1814e271a95 | 393 | |
Vigilance88 | 27:d1814e271a95 | 394 | |
Vigilance88 | 27:d1814e271a95 | 395 | case '4' : |
Vigilance88 | 27:d1814e271a95 | 396 | y-=0.01; |
Vigilance88 | 32:76c4d7bb2022 | 397 | |
Vigilance88 | 27:d1814e271a95 | 398 | break; |
Vigilance88 | 27:d1814e271a95 | 399 | |
Vigilance88 | 27:d1814e271a95 | 400 | case 'q' : |
Vigilance88 | 28:743485bb51e4 | 401 | case 'Q' : |
Vigilance88 | 28:743485bb51e4 | 402 | pc.printf("=> Quitting control... \r\n"); wait(1); |
Vigilance88 | 28:743485bb51e4 | 403 | stop_sampling(); |
Vigilance88 | 28:743485bb51e4 | 404 | stop_control(); |
Vigilance88 | 28:743485bb51e4 | 405 | pwm_motor1=0; pwm_motor2=0; |
Vigilance88 | 28:743485bb51e4 | 406 | pc.printf("Sampling and Control detached \n\r"); wait(1); |
Vigilance88 | 28:743485bb51e4 | 407 | pc.printf("Returning to Main Menu \r\n\n"); wait(1); |
Vigilance88 | 28:743485bb51e4 | 408 | mainMenu(); |
Vigilance88 | 28:743485bb51e4 | 409 | |
Vigilance88 | 27:d1814e271a95 | 410 | //running = false; |
Vigilance88 | 27:d1814e271a95 | 411 | break; |
Vigilance88 | 27:d1814e271a95 | 412 | }//end switch |
Vigilance88 | 28:743485bb51e4 | 413 | if(c!='q' && c!='Q'){ |
Vigilance88 | 27:d1814e271a95 | 414 | pc.printf("Reference position: %f and %f \r\n",x,y); |
Vigilance88 | 27:d1814e271a95 | 415 | pc.printf("Current position: %f and %f \r\n",current_x,current_y); |
Vigilance88 | 27:d1814e271a95 | 416 | pc.printf("Current angles: %f and %f \r\n",theta1,theta2); |
Vigilance88 | 27:d1814e271a95 | 417 | pc.printf("Error in angles: %f and %f \r\n",dtheta1,dtheta2); |
Vigilance88 | 27:d1814e271a95 | 418 | pc.printf("PID output: %f and %f \r\n",u1,u2); |
Vigilance88 | 27:d1814e271a95 | 419 | pc.printf("----------------------------------------\r\n\n"); |
Vigilance88 | 27:d1814e271a95 | 420 | } |
Vigilance88 | 28:743485bb51e4 | 421 | } |
Vigilance88 | 27:d1814e271a95 | 422 | //end if |
Vigilance88 | 21:d6a46315d5f5 | 423 | } |
Vigilance88 | 21:d6a46315d5f5 | 424 | //end of while loop |
Vigilance88 | 30:a9fdd3202ca2 | 425 | } |
Vigilance88 | 18:44905b008f44 | 426 | |
Vigilance88 | 21:d6a46315d5f5 | 427 | //Sample and Filter |
Vigilance88 | 21:d6a46315d5f5 | 428 | void sample_filter(void) |
Vigilance88 | 18:44905b008f44 | 429 | { |
Vigilance88 | 32:76c4d7bb2022 | 430 | emg_biceps = emg1.read(); //Biceps |
Vigilance88 | 32:76c4d7bb2022 | 431 | emg_triceps = emg2.read(); //Triceps |
Vigilance88 | 32:76c4d7bb2022 | 432 | emg_flexor = emg3.read(); //Flexor |
Vigilance88 | 32:76c4d7bb2022 | 433 | emg_extens = emg4.read(); //Extensor |
Vigilance88 | 21:d6a46315d5f5 | 434 | |
Vigilance88 | 21:d6a46315d5f5 | 435 | //Filter: high-pass -> notch -> rectify -> lowpass or moving average |
Vigilance88 | 22:1ba637601dc3 | 436 | // Can we use same biquadFilter (eg. highpass) for other muscles or does each muscle need its own biquad? |
Vigilance88 | 25:49ccdc98639a | 437 | 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 | 438 | 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 | 439 | 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 | 440 | biceps_power = abs(biceps_power); triceps_power = abs(triceps_power); flexor_power = abs(flexor_power); extens_power = abs(extens_power); |
Vigilance88 | 25:49ccdc98639a | 441 | 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 | 32:76c4d7bb2022 | 442 | biceps_power = biceps_power+0.1; triceps_power = triceps_power+0.1; flexor_power = flexor_power+1; extens_power = extens_power+1; |
Vigilance88 | 25:49ccdc98639a | 443 | |
Vigilance88 | 32:76c4d7bb2022 | 444 | scope.set(0,biceps_power); |
Vigilance88 | 32:76c4d7bb2022 | 445 | scope.set(1,triceps_power); |
Vigilance88 | 32:76c4d7bb2022 | 446 | scope.set(2,flexor_power); |
Vigilance88 | 32:76c4d7bb2022 | 447 | scope.set(3,extens_power); |
Vigilance88 | 29:948b0b14f6be | 448 | scope.send(); |
Vigilance88 | 32:76c4d7bb2022 | 449 | |
Vigilance88 | 32:76c4d7bb2022 | 450 | // on - offset. If above a value it is on. |
Vigilance88 | 32:76c4d7bb2022 | 451 | |
Vigilance88 | 32:76c4d7bb2022 | 452 | |
Vigilance88 | 21:d6a46315d5f5 | 453 | /* alternative for lowpass filter: moving average |
Vigilance88 | 21:d6a46315d5f5 | 454 | window=30; //30 samples |
Vigilance88 | 21:d6a46315d5f5 | 455 | int i=0; //buffer index |
Vigilance88 | 21:d6a46315d5f5 | 456 | bicepsbuffer[i]=biceps_power //fill array |
Vigilance88 | 21:d6a46315d5f5 | 457 | |
Vigilance88 | 21:d6a46315d5f5 | 458 | i++; |
Vigilance88 | 21:d6a46315d5f5 | 459 | if(i==window){ |
Vigilance88 | 21:d6a46315d5f5 | 460 | i=0; |
Vigilance88 | 21:d6a46315d5f5 | 461 | } |
Vigilance88 | 21:d6a46315d5f5 | 462 | |
Vigilance88 | 24:56db31267f10 | 463 | for(int x = 0; x < window; x++){ |
Vigilance88 | 24:56db31267f10 | 464 | avg1 += bicepsbuffer[x]; |
Vigilance88 | 24:56db31267f10 | 465 | } |
Vigilance88 | 24:56db31267f10 | 466 | avg1 = avg1/window; |
Vigilance88 | 21:d6a46315d5f5 | 467 | */ |
Vigilance88 | 21:d6a46315d5f5 | 468 | |
Vigilance88 | 18:44905b008f44 | 469 | } |
Vigilance88 | 18:44905b008f44 | 470 | |
Vigilance88 | 27:d1814e271a95 | 471 | |
Vigilance88 | 32:76c4d7bb2022 | 472 | void shoulder(){ |
Vigilance88 | 32:76c4d7bb2022 | 473 | pwm_motor1.write(0); |
Vigilance88 | 32:76c4d7bb2022 | 474 | Encoder1.reset(); |
Vigilance88 | 32:76c4d7bb2022 | 475 | done1 = true; |
Vigilance88 | 32:76c4d7bb2022 | 476 | pc.printf("Shoulder Limit hit - shutting down motor 1\r\n"); |
Vigilance88 | 32:76c4d7bb2022 | 477 | } |
Vigilance88 | 32:76c4d7bb2022 | 478 | |
Vigilance88 | 32:76c4d7bb2022 | 479 | void elbow(){ |
Vigilance88 | 32:76c4d7bb2022 | 480 | pwm_motor2.write(0); |
Vigilance88 | 32:76c4d7bb2022 | 481 | Encoder2.reset(); |
Vigilance88 | 32:76c4d7bb2022 | 482 | done2 = true; |
Vigilance88 | 32:76c4d7bb2022 | 483 | pc.printf("Elbow Limit hit - shutting down motor 2\r\n"); |
Vigilance88 | 32:76c4d7bb2022 | 484 | } |
Vigilance88 | 32:76c4d7bb2022 | 485 | |
Vigilance88 | 18:44905b008f44 | 486 | //Send arm to mechanical limits, and set encoder to 0. Then send arm to starting position. |
Vigilance88 | 19:0a3ee31dcdb4 | 487 | void calibrate_arm(void) |
Vigilance88 | 19:0a3ee31dcdb4 | 488 | { |
Vigilance88 | 28:743485bb51e4 | 489 | pc.printf("Calibrate_arm() entered\r\n"); |
Vigilance88 | 32:76c4d7bb2022 | 490 | red=0; blue=0; //Debug light is purple during arm calibration |
Vigilance88 | 32:76c4d7bb2022 | 491 | |
Vigilance88 | 32:76c4d7bb2022 | 492 | done1 = false; |
Vigilance88 | 32:76c4d7bb2022 | 493 | done2 = false; |
Vigilance88 | 26:fe3a5469dd6b | 494 | bool calibrating = true; |
Vigilance88 | 32:76c4d7bb2022 | 495 | |
Vigilance88 | 27:d1814e271a95 | 496 | pc.printf("To start arm calibration, press any key =>"); |
Vigilance88 | 27:d1814e271a95 | 497 | pc.getc(); |
Vigilance88 | 27:d1814e271a95 | 498 | pc.printf("\r\n Calibrating... \r\n"); |
Vigilance88 | 26:fe3a5469dd6b | 499 | dir_motor1=1; //cw |
Vigilance88 | 27:d1814e271a95 | 500 | dir_motor2=0; //cw |
Vigilance88 | 27:d1814e271a95 | 501 | pwm_motor1.write(0.2); //move upper arm slowly cw |
Vigilance88 | 27:d1814e271a95 | 502 | |
Vigilance88 | 26:fe3a5469dd6b | 503 | |
Vigilance88 | 26:fe3a5469dd6b | 504 | while(calibrating){ |
Vigilance88 | 32:76c4d7bb2022 | 505 | shoulder_limit.rise(&shoulder); |
Vigilance88 | 32:76c4d7bb2022 | 506 | elbow_limit.rise(&elbow); |
Vigilance88 | 27:d1814e271a95 | 507 | if(done1==true){ |
Vigilance88 | 27:d1814e271a95 | 508 | pwm_motor2.write(0.2); //move forearm slowly cw |
Vigilance88 | 27:d1814e271a95 | 509 | } |
Vigilance88 | 27:d1814e271a95 | 510 | |
Vigilance88 | 26:fe3a5469dd6b | 511 | if(done1 && done2){ |
Vigilance88 | 26:fe3a5469dd6b | 512 | calibrating=false; //Leave while loop when both limits are reached |
Vigilance88 | 26:fe3a5469dd6b | 513 | red=1; blue=1; //Turn debug light off when calibration complete |
Vigilance88 | 26:fe3a5469dd6b | 514 | } |
Vigilance88 | 27:d1814e271a95 | 515 | |
Vigilance88 | 27:d1814e271a95 | 516 | }//end while |
Vigilance88 | 32:76c4d7bb2022 | 517 | |
Vigilance88 | 27:d1814e271a95 | 518 | //TO DO: |
Vigilance88 | 32:76c4d7bb2022 | 519 | //mechanical angle limits -> pulses. If 40 degrees -> counts = floor( 40 * (2*pi/4200) ) |
Vigilance88 | 27:d1814e271a95 | 520 | //Encoder1.setPulses(100); //edited QEI library: added setPulses() |
Vigilance88 | 27:d1814e271a95 | 521 | //Encoder2.setPulses(100); //edited QEI library: added setPulses() |
Vigilance88 | 27:d1814e271a95 | 522 | //pc.printf("Elbow Limit hit - shutting down motor 2. Current pulsecount: %i \r\n",Encoder1.getPulses()); |
Vigilance88 | 31:7b8b8459bddc | 523 | |
Vigilance88 | 27:d1814e271a95 | 524 | wait(1); |
Vigilance88 | 28:743485bb51e4 | 525 | pc.printf("\n\r ------------------------ \n\r"); |
Vigilance88 | 27:d1814e271a95 | 526 | pc.printf("Arm Calibration Complete\r\n"); |
Vigilance88 | 28:743485bb51e4 | 527 | pc.printf(" ------------------------ \n\r"); |
Vigilance88 | 26:fe3a5469dd6b | 528 | |
Vigilance88 | 19:0a3ee31dcdb4 | 529 | } |
Vigilance88 | 19:0a3ee31dcdb4 | 530 | |
Vigilance88 | 21:d6a46315d5f5 | 531 | //EMG Maximum Voluntary Contraction measurement |
Vigilance88 | 25:49ccdc98639a | 532 | void emg_mvc() |
Vigilance88 | 25:49ccdc98639a | 533 | { |
Vigilance88 | 24:56db31267f10 | 534 | //double sampletime=0; |
Vigilance88 | 24:56db31267f10 | 535 | //sampletime=+SAMPLE_RATE; |
Vigilance88 | 24:56db31267f10 | 536 | // |
Vigilance88 | 24:56db31267f10 | 537 | // if(sampletime<5) |
Vigilance88 | 25:49ccdc98639a | 538 | //int muscle=1; |
Vigilance88 | 25:49ccdc98639a | 539 | //for(int index=0; index<2500;index++){ //measure 5 seconds@500hz = 2500 samples |
Vigilance88 | 25:49ccdc98639a | 540 | |
Vigilance88 | 24:56db31267f10 | 541 | if(muscle==1){ |
Vigilance88 | 24:56db31267f10 | 542 | |
Vigilance88 | 24:56db31267f10 | 543 | if(biceps_power>bicepsMVC){ |
Vigilance88 | 26:fe3a5469dd6b | 544 | //printf("+ "); |
Vigilance88 | 26:fe3a5469dd6b | 545 | printf("%s+ %s",GREEN_,_GREEN); |
Vigilance88 | 21:d6a46315d5f5 | 546 | bicepsMVC=biceps_power; |
Vigilance88 | 24:56db31267f10 | 547 | } |
Vigilance88 | 25:49ccdc98639a | 548 | else |
Vigilance88 | 25:49ccdc98639a | 549 | printf("- "); |
Vigilance88 | 24:56db31267f10 | 550 | } |
Vigilance88 | 24:56db31267f10 | 551 | |
Vigilance88 | 24:56db31267f10 | 552 | if(muscle==2){ |
Vigilance88 | 24:56db31267f10 | 553 | |
Vigilance88 | 24:56db31267f10 | 554 | if(triceps_power>tricepsMVC){ |
Vigilance88 | 26:fe3a5469dd6b | 555 | printf("%s+ %s",GREEN_,_GREEN); |
Vigilance88 | 24:56db31267f10 | 556 | tricepsMVC=triceps_power; |
Vigilance88 | 24:56db31267f10 | 557 | } |
Vigilance88 | 26:fe3a5469dd6b | 558 | else |
Vigilance88 | 26:fe3a5469dd6b | 559 | printf("- "); |
Vigilance88 | 24:56db31267f10 | 560 | } |
Vigilance88 | 24:56db31267f10 | 561 | |
Vigilance88 | 24:56db31267f10 | 562 | if(muscle==3){ |
Vigilance88 | 24:56db31267f10 | 563 | |
Vigilance88 | 24:56db31267f10 | 564 | if(flexor_power>flexorMVC){ |
Vigilance88 | 26:fe3a5469dd6b | 565 | printf("%s+ %s",GREEN_,_GREEN); |
Vigilance88 | 24:56db31267f10 | 566 | flexorMVC=flexor_power; |
Vigilance88 | 24:56db31267f10 | 567 | } |
Vigilance88 | 26:fe3a5469dd6b | 568 | else |
Vigilance88 | 26:fe3a5469dd6b | 569 | printf("- "); |
Vigilance88 | 24:56db31267f10 | 570 | } |
Vigilance88 | 24:56db31267f10 | 571 | |
Vigilance88 | 24:56db31267f10 | 572 | if(muscle==4){ |
Vigilance88 | 24:56db31267f10 | 573 | |
Vigilance88 | 24:56db31267f10 | 574 | if(extens_power>extensMVC){ |
Vigilance88 | 26:fe3a5469dd6b | 575 | printf("%s+ %s",GREEN_,_GREEN); |
Vigilance88 | 24:56db31267f10 | 576 | extensMVC=extens_power; |
Vigilance88 | 24:56db31267f10 | 577 | } |
Vigilance88 | 26:fe3a5469dd6b | 578 | else |
Vigilance88 | 26:fe3a5469dd6b | 579 | printf("- "); |
Vigilance88 | 24:56db31267f10 | 580 | } |
Vigilance88 | 25:49ccdc98639a | 581 | |
Vigilance88 | 25:49ccdc98639a | 582 | //} |
Vigilance88 | 25:49ccdc98639a | 583 | calibrate_time = calibrate_time + 0.002; |
Vigilance88 | 25:49ccdc98639a | 584 | |
Vigilance88 | 25:49ccdc98639a | 585 | |
Vigilance88 | 25:49ccdc98639a | 586 | |
Vigilance88 | 25:49ccdc98639a | 587 | } |
Vigilance88 | 25:49ccdc98639a | 588 | |
Vigilance88 | 25:49ccdc98639a | 589 | //EMG calibration |
Vigilance88 | 25:49ccdc98639a | 590 | void calibrate_emg() |
Vigilance88 | 25:49ccdc98639a | 591 | { |
Vigilance88 | 25:49ccdc98639a | 592 | Ticker timer; |
Vigilance88 | 25:49ccdc98639a | 593 | |
Vigilance88 | 25:49ccdc98639a | 594 | pc.printf("Testcode calibration \r\n"); |
Vigilance88 | 25:49ccdc98639a | 595 | wait(1); |
Vigilance88 | 25:49ccdc98639a | 596 | pc.printf("+ means current sample is higher than stored MVC\r\n"); |
Vigilance88 | 25:49ccdc98639a | 597 | pc.printf("- means current sample is lower than stored MVC\r\n"); |
Vigilance88 | 26:fe3a5469dd6b | 598 | wait(2); |
Vigilance88 | 28:743485bb51e4 | 599 | pc.printf("\r\n----------------\r\n "); |
Vigilance88 | 28:743485bb51e4 | 600 | pc.printf(" Biceps is first.\r\n "); |
Vigilance88 | 28:743485bb51e4 | 601 | pc.printf("----------------\r\n "); |
Vigilance88 | 28:743485bb51e4 | 602 | wait(1); |
Vigilance88 | 25:49ccdc98639a | 603 | pc.printf(" Press any key to begin... "); wait(1); |
Vigilance88 | 25:49ccdc98639a | 604 | char input; |
Vigilance88 | 25:49ccdc98639a | 605 | input=pc.getc(); |
Vigilance88 | 25:49ccdc98639a | 606 | pc.putc(input); |
Vigilance88 | 25:49ccdc98639a | 607 | pc.printf(" \r\n Starting in 3... \r\n"); wait(1); |
Vigilance88 | 25:49ccdc98639a | 608 | pc.printf(" \r\n Starting in 2... \r\n"); wait(1); |
Vigilance88 | 25:49ccdc98639a | 609 | pc.printf(" \r\n Starting in 1... \r\n"); wait(1); |
Vigilance88 | 25:49ccdc98639a | 610 | |
Vigilance88 | 25:49ccdc98639a | 611 | start_sampling(); |
Vigilance88 | 25:49ccdc98639a | 612 | muscle=1; |
Vigilance88 | 27:d1814e271a95 | 613 | timer.attach(&emg_mvc,SAMPLE_RATE); |
Vigilance88 | 25:49ccdc98639a | 614 | wait(5); |
Vigilance88 | 25:49ccdc98639a | 615 | timer.detach(); |
Vigilance88 | 26:fe3a5469dd6b | 616 | |
Vigilance88 | 26:fe3a5469dd6b | 617 | pc.printf("\r\n Measurement complete."); wait(1); |
Vigilance88 | 26:fe3a5469dd6b | 618 | pc.printf("\r\n Biceps MVC = %f \r\n",bicepsMVC); wait(1); |
Vigilance88 | 26:fe3a5469dd6b | 619 | pc.printf("Calibrate_emg() exited \r\n"); wait(1); |
Vigilance88 | 26:fe3a5469dd6b | 620 | pc.printf("Measured time: %f seconds \r\n\n",calibrate_time); |
Vigilance88 | 25:49ccdc98639a | 621 | calibrate_time=0; |
Vigilance88 | 25:49ccdc98639a | 622 | |
Vigilance88 | 25:49ccdc98639a | 623 | // Triceps: |
Vigilance88 | 26:fe3a5469dd6b | 624 | muscle=2; |
Vigilance88 | 28:743485bb51e4 | 625 | pc.printf("\r\n----------------\r\n "); |
Vigilance88 | 28:743485bb51e4 | 626 | pc.printf(" Triceps is next.\r\n "); |
Vigilance88 | 28:743485bb51e4 | 627 | pc.printf("----------------\r\n "); |
Vigilance88 | 28:743485bb51e4 | 628 | wait(1); |
Vigilance88 | 28:743485bb51e4 | 629 | |
Vigilance88 | 25:49ccdc98639a | 630 | pc.printf(" Press any key to begin... "); wait(1); |
Vigilance88 | 25:49ccdc98639a | 631 | input=pc.getc(); |
Vigilance88 | 25:49ccdc98639a | 632 | pc.putc(input); |
Vigilance88 | 25:49ccdc98639a | 633 | pc.printf(" \r\n Starting in 3... \r\n"); wait(1); |
Vigilance88 | 25:49ccdc98639a | 634 | pc.printf(" \r\n Starting in 2... \r\n"); wait(1); |
Vigilance88 | 25:49ccdc98639a | 635 | pc.printf(" \r\n Starting in 1... \r\n"); wait(1); |
Vigilance88 | 25:49ccdc98639a | 636 | start_sampling(); |
Vigilance88 | 25:49ccdc98639a | 637 | muscle=1; |
Vigilance88 | 25:49ccdc98639a | 638 | timer.attach(&emg_mvc,0.002); |
Vigilance88 | 25:49ccdc98639a | 639 | wait(5); |
Vigilance88 | 25:49ccdc98639a | 640 | timer.detach(); |
Vigilance88 | 25:49ccdc98639a | 641 | pc.printf("\r\n Triceps MVC = %f \r\n",tricepsMVC); |
Vigilance88 | 25:49ccdc98639a | 642 | |
Vigilance88 | 25:49ccdc98639a | 643 | pc.printf("Calibrate_emg() exited \r\n"); |
Vigilance88 | 25:49ccdc98639a | 644 | pc.printf("Measured time: %f seconds \r\n",calibrate_time); |
Vigilance88 | 25:49ccdc98639a | 645 | calibrate_time=0; |
Vigilance88 | 25:49ccdc98639a | 646 | |
Vigilance88 | 25:49ccdc98639a | 647 | //Flexor: |
Vigilance88 | 26:fe3a5469dd6b | 648 | muscle=3; |
Vigilance88 | 25:49ccdc98639a | 649 | //Extensor: |
Vigilance88 | 26:fe3a5469dd6b | 650 | muscle=4; |
Vigilance88 | 25:49ccdc98639a | 651 | |
Vigilance88 | 26:fe3a5469dd6b | 652 | //Stop sampling, detach ticker |
Vigilance88 | 25:49ccdc98639a | 653 | stop_sampling(); |
Vigilance88 | 24:56db31267f10 | 654 | |
Vigilance88 | 18:44905b008f44 | 655 | } |
Vigilance88 | 18:44905b008f44 | 656 | |
Vigilance88 | 18:44905b008f44 | 657 | |
Vigilance88 | 18:44905b008f44 | 658 | //Input error and Kp, Kd, Ki, output control signal |
Vigilance88 | 20:0ede3818e08e | 659 | double pid(double error, double kp, double ki, double kd,double &e_int, double &e_prev) |
vsluiter | 2:e314bb3b2d99 | 660 | { |
Vigilance88 | 20:0ede3818e08e | 661 | // Derivative |
Vigilance88 | 24:56db31267f10 | 662 | double e_der = (error-e_prev)/ CONTROL_RATE; |
Vigilance88 | 21:d6a46315d5f5 | 663 | e_der = derfilter.step(e_der); |
Vigilance88 | 21:d6a46315d5f5 | 664 | e_prev = error; |
Vigilance88 | 20:0ede3818e08e | 665 | // Integral |
Vigilance88 | 24:56db31267f10 | 666 | e_int = e_int + CONTROL_RATE * error; |
Vigilance88 | 20:0ede3818e08e | 667 | // PID |
Vigilance88 | 21:d6a46315d5f5 | 668 | return kp*error + ki*e_int + kd * e_der; |
Vigilance88 | 20:0ede3818e08e | 669 | |
Vigilance88 | 18:44905b008f44 | 670 | } |
Vigilance88 | 18:44905b008f44 | 671 | |
Vigilance88 | 20:0ede3818e08e | 672 | //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 | 673 | void control() |
Vigilance88 | 18:44905b008f44 | 674 | { |
Vigilance88 | 30:a9fdd3202ca2 | 675 | /* |
Vigilance88 | 30:a9fdd3202ca2 | 676 | |
Vigilance88 | 30:a9fdd3202ca2 | 677 | //normalize emg to value between 0-1 |
Vigilance88 | 30:a9fdd3202ca2 | 678 | biceps = (biceps - bicepsmin) / (bicepsmvc - bicepsmin) |
Vigilance88 | 30:a9fdd3202ca2 | 679 | biceps = (biceps - bicepsmin) / (bicepsmvc - bicepsmin) |
Vigilance88 | 30:a9fdd3202ca2 | 680 | biceps = (biceps - bicepsmin) / (bicepsmvc - bicepsmin) |
Vigilance88 | 30:a9fdd3202ca2 | 681 | biceps = (biceps - bicepsmin) / (bicepsmvc - bicepsmin) |
Vigilance88 | 30:a9fdd3202ca2 | 682 | |
Vigilance88 | 32:76c4d7bb2022 | 683 | //threshold detection! buffer? |
Vigilance88 | 32:76c4d7bb2022 | 684 | |
Vigilance88 | 30:a9fdd3202ca2 | 685 | //analyze emg (= velocity) |
Vigilance88 | 30:a9fdd3202ca2 | 686 | if (biceps>triceps && biceps > 0.1) |
Vigilance88 | 30:a9fdd3202ca2 | 687 | xdir = 0; |
Vigilance88 | 30:a9fdd3202ca2 | 688 | xpower = biceps; |
Vigilance88 | 30:a9fdd3202ca2 | 689 | else if (triceps>biceps && triceps>0.1) |
Vigilance88 | 30:a9fdd3202ca2 | 690 | xdir = 1; |
Vigilance88 | 30:a9fdd3202ca2 | 691 | xpower = triceps; |
Vigilance88 | 30:a9fdd3202ca2 | 692 | else |
Vigilance88 | 30:a9fdd3202ca2 | 693 | xpower=0; |
Vigilance88 | 30:a9fdd3202ca2 | 694 | |
Vigilance88 | 30:a9fdd3202ca2 | 695 | if (flexor>extensor && flexor > 0.1){ |
Vigilance88 | 30:a9fdd3202ca2 | 696 | ydir = 0; |
Vigilance88 | 30:a9fdd3202ca2 | 697 | ypower = flexor; |
Vigilance88 | 30:a9fdd3202ca2 | 698 | } |
Vigilance88 | 30:a9fdd3202ca2 | 699 | else if (extensor>flexor && extensor > 0.1){ |
Vigilance88 | 30:a9fdd3202ca2 | 700 | ydir = 1; |
Vigilance88 | 30:a9fdd3202ca2 | 701 | ypower = extensor; |
Vigilance88 | 30:a9fdd3202ca2 | 702 | } |
Vigilance88 | 30:a9fdd3202ca2 | 703 | else |
Vigilance88 | 30:a9fdd3202ca2 | 704 | ypower = 0; |
Vigilance88 | 30:a9fdd3202ca2 | 705 | |
Vigilance88 | 30:a9fdd3202ca2 | 706 | //We have power: the longer a signal is active, the further you go. So integrate to determine reference position |
Vigilance88 | 30:a9fdd3202ca2 | 707 | dx = xpower * CONTROL_RATE; |
Vigilance88 | 30:a9fdd3202ca2 | 708 | dy = ypower * CONTROL_RATE; |
Vigilance88 | 18:44905b008f44 | 709 | |
Vigilance88 | 30:a9fdd3202ca2 | 710 | //But: direction! Sum dx and dy but make sure xdir and ydir are considered. |
Vigilance88 | 30:a9fdd3202ca2 | 711 | if (xdir>0) |
Vigilance88 | 30:a9fdd3202ca2 | 712 | x += dx; |
Vigilance88 | 30:a9fdd3202ca2 | 713 | else |
Vigilance88 | 30:a9fdd3202ca2 | 714 | x += -dx; |
Vigilance88 | 30:a9fdd3202ca2 | 715 | |
Vigilance88 | 30:a9fdd3202ca2 | 716 | if (ydir>0) |
Vigilance88 | 30:a9fdd3202ca2 | 717 | y += dy; |
Vigilance88 | 30:a9fdd3202ca2 | 718 | else |
Vigilance88 | 30:a9fdd3202ca2 | 719 | y += -dy; |
Vigilance88 | 30:a9fdd3202ca2 | 720 | |
Vigilance88 | 30:a9fdd3202ca2 | 721 | //now we have x and y -> reference position. |
Vigilance88 | 30:a9fdd3202ca2 | 722 | |
Vigilance88 | 30:a9fdd3202ca2 | 723 | //Set limits to the error! |
Vigilance88 | 30:a9fdd3202ca2 | 724 | //lower limit: Negative error not allowed to go further. |
Vigilance88 | 30:a9fdd3202ca2 | 725 | if (theta1 < limitangle) |
Vigilance88 | 30:a9fdd3202ca2 | 726 | if (error1 > 0) |
Vigilance88 | 30:a9fdd3202ca2 | 727 | error1 = error1; |
Vigilance88 | 30:a9fdd3202ca2 | 728 | else |
Vigilance88 | 30:a9fdd3202ca2 | 729 | error1 = 0; |
Vigilance88 | 30:a9fdd3202ca2 | 730 | if (theta2 < limitangle) |
Vigilance88 | 30:a9fdd3202ca2 | 731 | same as above |
Vigilance88 | 30:a9fdd3202ca2 | 732 | |
Vigilance88 | 30:a9fdd3202ca2 | 733 | //upper limit: Positive error not allowed to go further |
Vigilance88 | 30:a9fdd3202ca2 | 734 | if (theta1 > limitangle) |
Vigilance88 | 30:a9fdd3202ca2 | 735 | if (error1 < 0 ) |
Vigilance88 | 30:a9fdd3202ca2 | 736 | error1 = error1; |
Vigilance88 | 30:a9fdd3202ca2 | 737 | else |
Vigilance88 | 30:a9fdd3202ca2 | 738 | error1 = 0; |
Vigilance88 | 30:a9fdd3202ca2 | 739 | if (theta2 > limitangle) |
Vigilance88 | 30:a9fdd3202ca2 | 740 | same as above |
Vigilance88 | 18:44905b008f44 | 741 | |
Vigilance88 | 30:a9fdd3202ca2 | 742 | |
Vigilance88 | 30:a9fdd3202ca2 | 743 | */ |
Vigilance88 | 30:a9fdd3202ca2 | 744 | |
Vigilance88 | 27:d1814e271a95 | 745 | //Current position - Encoder counts -> current angle -> Forward Kinematics |
Vigilance88 | 27:d1814e271a95 | 746 | rpc=(2*PI)/ENCODER1_CPR; //radians per count (resolution) - 2pi divided by 4200 |
Vigilance88 | 27:d1814e271a95 | 747 | theta1 = Encoder1.getPulses() * rpc; //multiply resolution with number of counts |
Vigilance88 | 27:d1814e271a95 | 748 | theta2 = Encoder2.getPulses() * rpc; |
Vigilance88 | 27:d1814e271a95 | 749 | current_x = l1 * cos(theta1) + l2 * cos(theta1 + theta2); |
Vigilance88 | 27:d1814e271a95 | 750 | current_y = l1 * sin(theta1) + l2 * sin(theta1 + theta2); |
Vigilance88 | 27:d1814e271a95 | 751 | |
Vigilance88 | 27:d1814e271a95 | 752 | |
Vigilance88 | 18:44905b008f44 | 753 | //calculate error (refpos-currentpos) currentpos = forward kinematics |
Vigilance88 | 27:d1814e271a95 | 754 | x_error = x - current_x; |
Vigilance88 | 27:d1814e271a95 | 755 | y_error = y - current_y; |
Vigilance88 | 27:d1814e271a95 | 756 | |
Vigilance88 | 27:d1814e271a95 | 757 | |
Vigilance88 | 27:d1814e271a95 | 758 | //inverse kinematics (refpos to refangle) |
Vigilance88 | 18:44905b008f44 | 759 | |
Vigilance88 | 27:d1814e271a95 | 760 | costheta2 = (pow(x,2) + pow(y,2) - pow(l1,2) - pow(l2,2)) / (2*l1*l2) ; |
Vigilance88 | 30:a9fdd3202ca2 | 761 | sintheta2 = sqrt( abs( 1 - pow(costheta2,2) ) ); |
Vigilance88 | 27:d1814e271a95 | 762 | |
Vigilance88 | 27:d1814e271a95 | 763 | |
Vigilance88 | 27:d1814e271a95 | 764 | dtheta2 = atan2(sintheta2,costheta2); |
Vigilance88 | 27:d1814e271a95 | 765 | |
Vigilance88 | 32:76c4d7bb2022 | 766 | double k1 = l1 + l2*costheta2; |
Vigilance88 | 32:76c4d7bb2022 | 767 | double k2 = l2*sintheta2; |
Vigilance88 | 32:76c4d7bb2022 | 768 | |
Vigilance88 | 32:76c4d7bb2022 | 769 | dtheta1 = atan2(y, x) - atan2(k2, k1); |
Vigilance88 | 32:76c4d7bb2022 | 770 | |
Vigilance88 | 32:76c4d7bb2022 | 771 | /* alternative: |
Vigilance88 | 27:d1814e271a95 | 772 | costheta1 = ( x * (l1 + l2 * costheta2) + y * l2 * sintheta2 ) / ( pow(x,2) + pow(y,2) ); |
Vigilance88 | 30:a9fdd3202ca2 | 773 | sintheta1 = sqrt( abs( 1 - pow(costheta1,2) ) ); |
Vigilance88 | 27:d1814e271a95 | 774 | |
Vigilance88 | 27:d1814e271a95 | 775 | dtheta1 = atan2(sintheta1,costheta1); |
Vigilance88 | 32:76c4d7bb2022 | 776 | */ |
Vigilance88 | 27:d1814e271a95 | 777 | |
Vigilance88 | 27:d1814e271a95 | 778 | //Angle error |
Vigilance88 | 27:d1814e271a95 | 779 | m1_error = dtheta1-theta1; |
Vigilance88 | 27:d1814e271a95 | 780 | m2_error = dtheta2-theta2; |
Vigilance88 | 27:d1814e271a95 | 781 | |
Vigilance88 | 18:44905b008f44 | 782 | |
Vigilance88 | 18:44905b008f44 | 783 | //PID controller |
Vigilance88 | 24:56db31267f10 | 784 | |
Vigilance88 | 24:56db31267f10 | 785 | u1=pid(m1_error,m1_kp,m1_ki,m1_kd,m1_e_int,m1_e_prev); //motor 1 |
Vigilance88 | 24:56db31267f10 | 786 | u2=pid(m2_error,m2_kp,m2_ki,m2_kd,m2_e_int,m2_e_prev); //motor 2 |
Vigilance88 | 21:d6a46315d5f5 | 787 | |
Vigilance88 | 27:d1814e271a95 | 788 | keep_in_range(&u1,-0.6,0.6); //keep u between -1 and 1, sign = direction, PWM = 0-1 |
Vigilance88 | 27:d1814e271a95 | 789 | keep_in_range(&u2,-0.6,0.6); |
Vigilance88 | 21:d6a46315d5f5 | 790 | |
Vigilance88 | 21:d6a46315d5f5 | 791 | //send PWM and DIR to motor 1 |
Vigilance88 | 21:d6a46315d5f5 | 792 | dir_motor1 = u1>0 ? 1 : 0; //conditional statement dir_motor1 = [condition] ? [if met 1] : [else 0]], same as if else below. |
Vigilance88 | 21:d6a46315d5f5 | 793 | pwm_motor1.write(abs(u1)); |
Vigilance88 | 21:d6a46315d5f5 | 794 | |
Vigilance88 | 21:d6a46315d5f5 | 795 | //send PWM and DIR to motor 2 |
Vigilance88 | 27:d1814e271a95 | 796 | dir_motor2 = u2>0 ? 0 : 1; //conditional statement, same as if else below |
Vigilance88 | 25:49ccdc98639a | 797 | pwm_motor2.write(abs(u2)); |
Vigilance88 | 21:d6a46315d5f5 | 798 | |
Vigilance88 | 21:d6a46315d5f5 | 799 | /*if(u1 > 0) |
Vigilance88 | 21:d6a46315d5f5 | 800 | { |
Vigilance88 | 21:d6a46315d5f5 | 801 | dir_motor1 = 0; |
Vigilance88 | 21:d6a46315d5f5 | 802 | else{ |
Vigilance88 | 21:d6a46315d5f5 | 803 | dir_motor1 = 1; |
Vigilance88 | 21:d6a46315d5f5 | 804 | } |
Vigilance88 | 21:d6a46315d5f5 | 805 | } |
Vigilance88 | 21:d6a46315d5f5 | 806 | pwm_motor1.write(abs(u1)); |
Vigilance88 | 21:d6a46315d5f5 | 807 | |
Vigilance88 | 21:d6a46315d5f5 | 808 | |
Vigilance88 | 21:d6a46315d5f5 | 809 | if(u2 > 0) |
Vigilance88 | 21:d6a46315d5f5 | 810 | { |
Vigilance88 | 21:d6a46315d5f5 | 811 | dir_motor1 = 1; |
Vigilance88 | 21:d6a46315d5f5 | 812 | else{ |
Vigilance88 | 21:d6a46315d5f5 | 813 | dir_motor1 = 0; |
Vigilance88 | 21:d6a46315d5f5 | 814 | } |
Vigilance88 | 21:d6a46315d5f5 | 815 | } |
Vigilance88 | 21:d6a46315d5f5 | 816 | pwm_motor1.write(abs(u2));*/ |
Vigilance88 | 21:d6a46315d5f5 | 817 | |
Vigilance88 | 18:44905b008f44 | 818 | } |
Vigilance88 | 18:44905b008f44 | 819 | |
Vigilance88 | 32:76c4d7bb2022 | 820 | void dlscontrol() |
Vigilance88 | 32:76c4d7bb2022 | 821 | { |
Vigilance88 | 32:76c4d7bb2022 | 822 | /* |
Vigilance88 | 32:76c4d7bb2022 | 823 | |
Vigilance88 | 32:76c4d7bb2022 | 824 | //normalize emg to value between 0-1 |
Vigilance88 | 32:76c4d7bb2022 | 825 | biceps = (biceps - bicepsmin) / (bicepsmvc - bicepsmin) |
Vigilance88 | 32:76c4d7bb2022 | 826 | biceps = (biceps - bicepsmin) / (bicepsmvc - bicepsmin) |
Vigilance88 | 32:76c4d7bb2022 | 827 | biceps = (biceps - bicepsmin) / (bicepsmvc - bicepsmin) |
Vigilance88 | 32:76c4d7bb2022 | 828 | biceps = (biceps - bicepsmin) / (bicepsmvc - bicepsmin) |
Vigilance88 | 32:76c4d7bb2022 | 829 | |
Vigilance88 | 32:76c4d7bb2022 | 830 | //analyze emg (= velocity) |
Vigilance88 | 32:76c4d7bb2022 | 831 | if (biceps>triceps && biceps > 0.1) |
Vigilance88 | 32:76c4d7bb2022 | 832 | xdir = 0; |
Vigilance88 | 32:76c4d7bb2022 | 833 | xpower = biceps; |
Vigilance88 | 32:76c4d7bb2022 | 834 | else if (triceps>biceps && triceps>0.1) |
Vigilance88 | 32:76c4d7bb2022 | 835 | xdir = 1; |
Vigilance88 | 32:76c4d7bb2022 | 836 | xpower = triceps; |
Vigilance88 | 32:76c4d7bb2022 | 837 | else |
Vigilance88 | 32:76c4d7bb2022 | 838 | xpower=0; |
Vigilance88 | 32:76c4d7bb2022 | 839 | |
Vigilance88 | 32:76c4d7bb2022 | 840 | if (flexor>extensor && flexor > 0.1){ |
Vigilance88 | 32:76c4d7bb2022 | 841 | ydir = 0; |
Vigilance88 | 32:76c4d7bb2022 | 842 | ypower = flexor; |
Vigilance88 | 32:76c4d7bb2022 | 843 | } |
Vigilance88 | 32:76c4d7bb2022 | 844 | else if (extensor>flexor && extensor > 0.1){ |
Vigilance88 | 32:76c4d7bb2022 | 845 | ydir = 1; |
Vigilance88 | 32:76c4d7bb2022 | 846 | ypower = extensor; |
Vigilance88 | 32:76c4d7bb2022 | 847 | } |
Vigilance88 | 32:76c4d7bb2022 | 848 | else |
Vigilance88 | 32:76c4d7bb2022 | 849 | ypower = 0; |
Vigilance88 | 32:76c4d7bb2022 | 850 | |
Vigilance88 | 32:76c4d7bb2022 | 851 | //We have power: the longer a signal is active, the further you go. So integrate to determine reference position |
Vigilance88 | 32:76c4d7bb2022 | 852 | dx = xpower * CONTROL_RATE; |
Vigilance88 | 32:76c4d7bb2022 | 853 | dy = ypower * CONTROL_RATE; |
Vigilance88 | 32:76c4d7bb2022 | 854 | |
Vigilance88 | 32:76c4d7bb2022 | 855 | //But: direction! Sum dx and dy but make sure xdir and ydir are considered. |
Vigilance88 | 32:76c4d7bb2022 | 856 | if (xdir>0) |
Vigilance88 | 32:76c4d7bb2022 | 857 | x += dx; |
Vigilance88 | 32:76c4d7bb2022 | 858 | else |
Vigilance88 | 32:76c4d7bb2022 | 859 | x += -dx; |
Vigilance88 | 32:76c4d7bb2022 | 860 | |
Vigilance88 | 32:76c4d7bb2022 | 861 | if (ydir>0) |
Vigilance88 | 32:76c4d7bb2022 | 862 | y += dy; |
Vigilance88 | 32:76c4d7bb2022 | 863 | else |
Vigilance88 | 32:76c4d7bb2022 | 864 | y += -dy; |
Vigilance88 | 32:76c4d7bb2022 | 865 | |
Vigilance88 | 32:76c4d7bb2022 | 866 | //now we have x and y -> reference position. |
Vigilance88 | 32:76c4d7bb2022 | 867 | |
Vigilance88 | 32:76c4d7bb2022 | 868 | //Set limits to the error! |
Vigilance88 | 32:76c4d7bb2022 | 869 | //lower limit: Negative error not allowed to go further. |
Vigilance88 | 32:76c4d7bb2022 | 870 | if (theta1 < limitangle) |
Vigilance88 | 32:76c4d7bb2022 | 871 | if (error1 > 0) |
Vigilance88 | 32:76c4d7bb2022 | 872 | error1 = error1; |
Vigilance88 | 32:76c4d7bb2022 | 873 | else |
Vigilance88 | 32:76c4d7bb2022 | 874 | error1 = 0; |
Vigilance88 | 32:76c4d7bb2022 | 875 | if (theta2 < limitangle) |
Vigilance88 | 32:76c4d7bb2022 | 876 | same as above |
Vigilance88 | 32:76c4d7bb2022 | 877 | |
Vigilance88 | 32:76c4d7bb2022 | 878 | //upper limit: Positive error not allowed to go further |
Vigilance88 | 32:76c4d7bb2022 | 879 | if (theta1 > limitangle) |
Vigilance88 | 32:76c4d7bb2022 | 880 | if (error1 < 0 ) |
Vigilance88 | 32:76c4d7bb2022 | 881 | error1 = error1; |
Vigilance88 | 32:76c4d7bb2022 | 882 | else |
Vigilance88 | 32:76c4d7bb2022 | 883 | error1 = 0; |
Vigilance88 | 32:76c4d7bb2022 | 884 | if (theta2 > limitangle) |
Vigilance88 | 32:76c4d7bb2022 | 885 | same as above |
Vigilance88 | 32:76c4d7bb2022 | 886 | |
Vigilance88 | 32:76c4d7bb2022 | 887 | |
Vigilance88 | 32:76c4d7bb2022 | 888 | */ |
Vigilance88 | 32:76c4d7bb2022 | 889 | |
Vigilance88 | 32:76c4d7bb2022 | 890 | //Current position - Encoder counts -> current angle -> Forward Kinematics |
Vigilance88 | 32:76c4d7bb2022 | 891 | rpc=(2*PI)/ENCODER1_CPR; //radians per count (resolution) - 2pi divided by 4200 |
Vigilance88 | 32:76c4d7bb2022 | 892 | theta1 = Encoder1.getPulses() * rpc; //multiply resolution with number of counts |
Vigilance88 | 32:76c4d7bb2022 | 893 | theta2 = Encoder2.getPulses() * rpc; |
Vigilance88 | 32:76c4d7bb2022 | 894 | current_x = l1 * cos(theta1) + l2 * cos(theta1 + theta2); |
Vigilance88 | 32:76c4d7bb2022 | 895 | current_y = l1 * sin(theta1) + l2 * sin(theta1 + theta2); |
Vigilance88 | 32:76c4d7bb2022 | 896 | |
Vigilance88 | 32:76c4d7bb2022 | 897 | |
Vigilance88 | 32:76c4d7bb2022 | 898 | //calculate error (refpos-currentpos) currentpos = forward kinematics |
Vigilance88 | 32:76c4d7bb2022 | 899 | x_error = x - current_x; |
Vigilance88 | 32:76c4d7bb2022 | 900 | y_error = y - current_y; |
Vigilance88 | 32:76c4d7bb2022 | 901 | |
Vigilance88 | 32:76c4d7bb2022 | 902 | |
Vigilance88 | 32:76c4d7bb2022 | 903 | //inverse kinematics (error in position to error in angles) |
Vigilance88 | 32:76c4d7bb2022 | 904 | dls1= -(l2*pow(lambda,2)*sin(theta1 + theta2) + l1*pow(lambda,2)*sin(theta1) + l1*pow(l2,2)*pow(cos(theta1 + theta2),2)*sin(theta1) - l1*pow(l2,2)*cos(theta1 + theta2)*sin(theta1 + theta2)*cos(theta1))/(pow(lambda,4) + 2*pow(l2,2)*pow(lambda,2)*pow(cos(theta1 + theta2),2) + 2*pow(l2,2)*pow(lambda,2)*pow(sin(theta1 + theta2),2) + pow(l1,2)*pow(lambda,2)*pow(cos(theta1),2) + pow(l1,2)*pow(lambda,2)*pow(sin(theta1),2) + pow(l1,2)*pow(l2,2)*pow(cos(theta1 + theta2),2)*pow(sin(theta1),2) + pow(l1,2)*pow(l2,2)*pow(sin(theta1 + theta2),2)*pow(cos(theta1),2) + 2*l1*l2*pow(lambda,2)*cos(theta1 + theta2)*cos(theta1) + 2*l1*l2*pow(lambda,2)*sin(theta1 + theta2)*sin(theta1) - 2*pow(l1,2)*pow(l2,2)*cos(theta1 + theta2)*sin(theta1 + theta2)*cos(theta1)*sin(theta1)); |
Vigilance88 | 32:76c4d7bb2022 | 905 | /* |
Vigilance88 | 32:76c4d7bb2022 | 906 | dls2= (l2*pow(lambda,2)*cos(theta1 + theta2) + l1*pow(lambda,2)*cos(theta1) + l1*pow(l2,2)*sin(theta1 + theta2)^2*cos(theta1) - l1*pow(l2,2)*cos(theta1 + theta2)*sin(theta1 + theta2)*sin(theta1))/(pow(lambda,4) + 2*pow(l2,2)*pow(lambda,2)*pow(cos(theta1 + theta2),2) + 2*l2^2*pow(lambda,2)*pow(sin(theta1 + theta2),2) + pow(l1,2)*pow(lambda,2)*cos(theta1)^2 + pow(l1,2)*pow(lambda,2)*pow(sin(theta1),2) + pow(l1,2)*pow(l2,2)*pow(cos(theta1 + theta2),2)*sin(theta1)^2 + l1^2*l2^2*sin(theta1 + theta2)^2*cos(theta1)^2 + 2*l1*l2*pow(lambda,2)*cos(theta1 + theta2)*cos(theta1) + 2*l1*l2*pow(lambda,2)*sin(theta1 + theta2)*sin(theta1) - 2*l1^2*l2^2*cos(theta1 + theta2)*sin(theta1 + theta2)*cos(theta1)*sin(theta1)); |
Vigilance88 | 32:76c4d7bb2022 | 907 | dls3= -(l2*pow(lambda,2)*sin(theta1 + theta2) - l1*pow(l2,2)*cos(theta1 + theta2)^2*sin(theta1) + pow(l1,2)*l2*sin(theta1 + theta2)*pow(cos(theta1),2) - pow(l1,2)*l2*cos(theta1 + theta2)*cos(theta1)*sin(theta1) + l1*pow(l2,2)*cos(theta1 + theta2)*sin(theta1 + theta2)*cos(theta1))/(pow(lambda,4) + 2*pow(l2,2)*pow(lambda,2)*pow(cos(theta1 + theta2),2) + 2*pow(l2,2)*pow(lambda,2)*pow(sin(theta1 + theta2),2) + pow(l1,2)*pow(lambda,2)*cos(theta1)^2 + l1^2*lambda^2*sin(theta1)^2 + l1^2*l2^2*cos(theta1 + theta2)^2*sin(theta1)^2 + l1^2*l2^2*sin(theta1 + theta2)^2*cos(theta1)^2 + 2*l1*l2*pow(lambda,2)*cos(theta1 + theta2)*cos(theta1) + 2*l1*l2*pow(lambda,2)*sin(theta1 + theta2)*sin(theta1) - 2*l1^2*l2^2*cos(theta1 + theta2)*sin(theta1 + theta2)*cos(theta1)*sin(theta1)); |
Vigilance88 | 32:76c4d7bb2022 | 908 | dls4= (l2*pow(lambda,2)*cos(theta1 + theta2) - l1*pow(l2,2)*sin(theta1 + theta2)^2*cos(theta1) + pow(l1,2)*l2*cos(theta1 + theta2)*pow(sin(theta1),2) - pow(l1,2)*l2*sin(theta1 + theta2)*cos(theta1)*sin(theta1) + l1*pow(l2,2)*cos(theta1 + theta2)*sin(theta1 + theta2)*sin(theta1))/(pow(lambda,4) + 2*pow(l2,2)*pow(lambda,2)*pow(cos(theta1 + theta2),2) + 2*pow(l2,2)*pow(lambda,2)*pow(sin(theta1 + theta2),2) + pow(l1,2)*pow(lambda,2)*cos(theta1)^2 + l1^2*lambda^2*sin(theta1)^2 + l1^2*l2^2*cos(theta1 + theta2)^2*sin(theta1)^2 + l1^2*l2^2*sin(theta1 + theta2)^2*cos(theta1)^2 + 2*l1*l2*pow(lambda,2)*cos(theta1 + theta2)*cos(theta1) + 2*l1*l2*pow(lambda,2)*sin(theta1 + theta2)*sin(theta1) - 2*l1^2*l2^2*cos(theta1 + theta2)*sin(theta1 + theta2)*cos(theta1)*sin(theta1)); |
Vigilance88 | 32:76c4d7bb2022 | 909 | */ |
Vigilance88 | 32:76c4d7bb2022 | 910 | |
Vigilance88 | 32:76c4d7bb2022 | 911 | q1_error = dls1 * x_error + dls2 * y_error; |
Vigilance88 | 32:76c4d7bb2022 | 912 | q2_error = dls3 * x_error + dls4 * y_error; |
Vigilance88 | 32:76c4d7bb2022 | 913 | |
Vigilance88 | 32:76c4d7bb2022 | 914 | //Angle error |
Vigilance88 | 32:76c4d7bb2022 | 915 | m1_error = q1_error; |
Vigilance88 | 32:76c4d7bb2022 | 916 | m2_error = q2_error; |
Vigilance88 | 32:76c4d7bb2022 | 917 | |
Vigilance88 | 32:76c4d7bb2022 | 918 | |
Vigilance88 | 32:76c4d7bb2022 | 919 | //PID controller |
Vigilance88 | 32:76c4d7bb2022 | 920 | |
Vigilance88 | 32:76c4d7bb2022 | 921 | u1=pid(m1_error,m1_kp,m1_ki,m1_kd,m1_e_int,m1_e_prev); //motor 1 |
Vigilance88 | 32:76c4d7bb2022 | 922 | u2=pid(m2_error,m2_kp,m2_ki,m2_kd,m2_e_int,m2_e_prev); //motor 2 |
Vigilance88 | 32:76c4d7bb2022 | 923 | |
Vigilance88 | 32:76c4d7bb2022 | 924 | keep_in_range(&u1,-0.6,0.6); //keep u between -1 and 1, sign = direction, PWM = 0-1 |
Vigilance88 | 32:76c4d7bb2022 | 925 | keep_in_range(&u2,-0.6,0.6); |
Vigilance88 | 32:76c4d7bb2022 | 926 | |
Vigilance88 | 32:76c4d7bb2022 | 927 | //send PWM and DIR to motor 1 |
Vigilance88 | 32:76c4d7bb2022 | 928 | dir_motor1 = u1>0 ? 1 : 0; //conditional statement dir_motor1 = [condition] ? [if met 1] : [else 0]], same as if else below. |
Vigilance88 | 32:76c4d7bb2022 | 929 | pwm_motor1.write(abs(u1)); |
Vigilance88 | 32:76c4d7bb2022 | 930 | |
Vigilance88 | 32:76c4d7bb2022 | 931 | //send PWM and DIR to motor 2 |
Vigilance88 | 32:76c4d7bb2022 | 932 | dir_motor2 = u2>0 ? 0 : 1; //conditional statement, same as if else below |
Vigilance88 | 32:76c4d7bb2022 | 933 | pwm_motor2.write(abs(u2)); |
Vigilance88 | 32:76c4d7bb2022 | 934 | |
Vigilance88 | 32:76c4d7bb2022 | 935 | /*if(u1 > 0) |
Vigilance88 | 32:76c4d7bb2022 | 936 | { |
Vigilance88 | 32:76c4d7bb2022 | 937 | dir_motor1 = 0; |
Vigilance88 | 32:76c4d7bb2022 | 938 | else{ |
Vigilance88 | 32:76c4d7bb2022 | 939 | dir_motor1 = 1; |
Vigilance88 | 32:76c4d7bb2022 | 940 | } |
Vigilance88 | 32:76c4d7bb2022 | 941 | } |
Vigilance88 | 32:76c4d7bb2022 | 942 | pwm_motor1.write(abs(u1)); |
Vigilance88 | 32:76c4d7bb2022 | 943 | |
Vigilance88 | 32:76c4d7bb2022 | 944 | |
Vigilance88 | 32:76c4d7bb2022 | 945 | if(u2 > 0) |
Vigilance88 | 32:76c4d7bb2022 | 946 | { |
Vigilance88 | 32:76c4d7bb2022 | 947 | dir_motor1 = 1; |
Vigilance88 | 32:76c4d7bb2022 | 948 | else{ |
Vigilance88 | 32:76c4d7bb2022 | 949 | dir_motor1 = 0; |
Vigilance88 | 32:76c4d7bb2022 | 950 | } |
Vigilance88 | 32:76c4d7bb2022 | 951 | } |
Vigilance88 | 32:76c4d7bb2022 | 952 | pwm_motor1.write(abs(u2));*/ |
Vigilance88 | 32:76c4d7bb2022 | 953 | |
Vigilance88 | 32:76c4d7bb2022 | 954 | } |
Vigilance88 | 32:76c4d7bb2022 | 955 | |
Vigilance88 | 26:fe3a5469dd6b | 956 | void mainMenu() |
Vigilance88 | 26:fe3a5469dd6b | 957 | { |
Vigilance88 | 28:743485bb51e4 | 958 | //Title Box |
Vigilance88 | 26:fe3a5469dd6b | 959 | pc.putc(201); |
Vigilance88 | 26:fe3a5469dd6b | 960 | for(int j=0;j<33;j++){ |
Vigilance88 | 26:fe3a5469dd6b | 961 | pc.putc(205); |
Vigilance88 | 26:fe3a5469dd6b | 962 | } |
Vigilance88 | 26:fe3a5469dd6b | 963 | pc.putc(187); |
Vigilance88 | 26:fe3a5469dd6b | 964 | pc.printf("\n\r"); |
Vigilance88 | 28:743485bb51e4 | 965 | pc.putc(186); pc.printf(" Main Menu "); pc.putc(186); |
Vigilance88 | 26:fe3a5469dd6b | 966 | pc.printf("\n\r"); |
Vigilance88 | 26:fe3a5469dd6b | 967 | pc.putc(200); |
Vigilance88 | 26:fe3a5469dd6b | 968 | for(int k=0;k<33;k++){ |
Vigilance88 | 26:fe3a5469dd6b | 969 | pc.putc(205); |
Vigilance88 | 26:fe3a5469dd6b | 970 | } |
Vigilance88 | 26:fe3a5469dd6b | 971 | pc.putc(188); |
Vigilance88 | 26:fe3a5469dd6b | 972 | |
Vigilance88 | 26:fe3a5469dd6b | 973 | pc.printf("\n\r"); |
Vigilance88 | 26:fe3a5469dd6b | 974 | //endbox |
Vigilance88 | 28:743485bb51e4 | 975 | wait(1); |
Vigilance88 | 28:743485bb51e4 | 976 | pc.printf("[C]alibration\r\n"); wait(0.2); |
Vigilance88 | 28:743485bb51e4 | 977 | pc.printf("[S]tart Control with buttons\r\n"); wait(0.2); |
Vigilance88 | 28:743485bb51e4 | 978 | pc.printf("[Q]uit Robot Program\r\n"); wait(0.2); |
Vigilance88 | 28:743485bb51e4 | 979 | pc.printf("[R]ed LED\r\n"); wait(0.2); |
Vigilance88 | 28:743485bb51e4 | 980 | pc.printf("[G]reen LED\r\n"); wait(0.2); |
Vigilance88 | 28:743485bb51e4 | 981 | pc.printf("[B]lue LED\r\n"); wait(0.2); |
Vigilance88 | 28:743485bb51e4 | 982 | pc.printf("Please make a choice => \r\n"); |
Vigilance88 | 26:fe3a5469dd6b | 983 | } |
Vigilance88 | 24:56db31267f10 | 984 | |
Vigilance88 | 24:56db31267f10 | 985 | //Start sampling |
Vigilance88 | 24:56db31267f10 | 986 | void start_sampling(void) |
Vigilance88 | 24:56db31267f10 | 987 | { |
Vigilance88 | 24:56db31267f10 | 988 | sample_timer.attach(&sample_filter,SAMPLE_RATE); //500 Hz EMG |
Vigilance88 | 26:fe3a5469dd6b | 989 | |
Vigilance88 | 26:fe3a5469dd6b | 990 | //Debug LED will be green when sampling is active |
Vigilance88 | 26:fe3a5469dd6b | 991 | green=0; |
Vigilance88 | 25:49ccdc98639a | 992 | pc.printf("||- started sampling -|| \r\n"); |
Vigilance88 | 24:56db31267f10 | 993 | } |
Vigilance88 | 24:56db31267f10 | 994 | |
Vigilance88 | 24:56db31267f10 | 995 | //stop sampling |
Vigilance88 | 24:56db31267f10 | 996 | void stop_sampling(void) |
Vigilance88 | 24:56db31267f10 | 997 | { |
Vigilance88 | 24:56db31267f10 | 998 | sample_timer.detach(); |
Vigilance88 | 26:fe3a5469dd6b | 999 | |
Vigilance88 | 26:fe3a5469dd6b | 1000 | //Debug LED will be turned off when sampling stops |
Vigilance88 | 26:fe3a5469dd6b | 1001 | green=1; |
Vigilance88 | 25:49ccdc98639a | 1002 | pc.printf("||- stopped sampling -|| \r\n"); |
Vigilance88 | 24:56db31267f10 | 1003 | } |
Vigilance88 | 24:56db31267f10 | 1004 | |
Vigilance88 | 18:44905b008f44 | 1005 | //Start control |
Vigilance88 | 18:44905b008f44 | 1006 | void start_control(void) |
Vigilance88 | 18:44905b008f44 | 1007 | { |
Vigilance88 | 27:d1814e271a95 | 1008 | control_timer.attach(&control,CONTROL_RATE); //100 Hz control |
Vigilance88 | 26:fe3a5469dd6b | 1009 | |
Vigilance88 | 26:fe3a5469dd6b | 1010 | //Debug LED will be blue when control is on. If sampling and control are on -> blue + green = cyan. |
Vigilance88 | 26:fe3a5469dd6b | 1011 | blue=0; |
Vigilance88 | 26:fe3a5469dd6b | 1012 | pc.printf("||- started control -|| \r\n"); |
Vigilance88 | 18:44905b008f44 | 1013 | } |
Vigilance88 | 18:44905b008f44 | 1014 | |
Vigilance88 | 18:44905b008f44 | 1015 | //stop control |
Vigilance88 | 18:44905b008f44 | 1016 | void stop_control(void) |
Vigilance88 | 18:44905b008f44 | 1017 | { |
Vigilance88 | 18:44905b008f44 | 1018 | control_timer.detach(); |
Vigilance88 | 26:fe3a5469dd6b | 1019 | |
Vigilance88 | 26:fe3a5469dd6b | 1020 | //Debug LED will be off when control is off |
Vigilance88 | 26:fe3a5469dd6b | 1021 | blue=1; |
Vigilance88 | 26:fe3a5469dd6b | 1022 | pc.printf("||- stopped control -|| \r\n"); |
vsluiter | 2:e314bb3b2d99 | 1023 | } |
vsluiter | 0:32bb76391d89 | 1024 | |
Vigilance88 | 21:d6a46315d5f5 | 1025 | |
Vigilance88 | 21:d6a46315d5f5 | 1026 | void calibrate() |
vsluiter | 0:32bb76391d89 | 1027 | { |
Vigilance88 | 21:d6a46315d5f5 | 1028 | |
Vigilance88 | 21:d6a46315d5f5 | 1029 | } |
tomlankhorst | 15:0da764eea774 | 1030 | |
Vigilance88 | 26:fe3a5469dd6b | 1031 | //Clears the putty (or other terminal) window |
Vigilance88 | 26:fe3a5469dd6b | 1032 | void clearTerminal() |
Vigilance88 | 26:fe3a5469dd6b | 1033 | { |
Vigilance88 | 26:fe3a5469dd6b | 1034 | pc.putc(27); |
Vigilance88 | 26:fe3a5469dd6b | 1035 | pc.printf("[2J"); // clear screen |
Vigilance88 | 26:fe3a5469dd6b | 1036 | pc.putc(27); // ESC |
Vigilance88 | 26:fe3a5469dd6b | 1037 | pc.printf("[H"); // cursor to home |
Vigilance88 | 26:fe3a5469dd6b | 1038 | } |
Vigilance88 | 21:d6a46315d5f5 | 1039 | |
Vigilance88 | 30:a9fdd3202ca2 | 1040 | |
Vigilance88 | 30:a9fdd3202ca2 | 1041 | void controlMenu() |
Vigilance88 | 30:a9fdd3202ca2 | 1042 | { |
Vigilance88 | 30:a9fdd3202ca2 | 1043 | //Title Box |
Vigilance88 | 30:a9fdd3202ca2 | 1044 | pc.putc(201); |
Vigilance88 | 30:a9fdd3202ca2 | 1045 | for(int j=0;j<33;j++){ |
Vigilance88 | 30:a9fdd3202ca2 | 1046 | pc.putc(205); |
Vigilance88 | 30:a9fdd3202ca2 | 1047 | } |
Vigilance88 | 30:a9fdd3202ca2 | 1048 | pc.putc(187); |
Vigilance88 | 30:a9fdd3202ca2 | 1049 | pc.printf("\n\r"); |
Vigilance88 | 30:a9fdd3202ca2 | 1050 | pc.putc(186); pc.printf(" Control Menu "); pc.putc(186); |
Vigilance88 | 30:a9fdd3202ca2 | 1051 | pc.printf("\n\r"); |
Vigilance88 | 30:a9fdd3202ca2 | 1052 | pc.putc(200); |
Vigilance88 | 30:a9fdd3202ca2 | 1053 | for(int k=0;k<33;k++){ |
Vigilance88 | 30:a9fdd3202ca2 | 1054 | pc.putc(205); |
Vigilance88 | 30:a9fdd3202ca2 | 1055 | } |
Vigilance88 | 30:a9fdd3202ca2 | 1056 | pc.putc(188); |
Vigilance88 | 30:a9fdd3202ca2 | 1057 | |
Vigilance88 | 30:a9fdd3202ca2 | 1058 | pc.printf("\n\r"); |
Vigilance88 | 30:a9fdd3202ca2 | 1059 | //endbox |
Vigilance88 | 30:a9fdd3202ca2 | 1060 | pc.printf("1) Move Arm Left\r\n"); |
Vigilance88 | 30:a9fdd3202ca2 | 1061 | pc.printf("2) Move Arm Right\r\n"); |
Vigilance88 | 30:a9fdd3202ca2 | 1062 | pc.printf("3) Move Arm Up\r\n"); |
Vigilance88 | 30:a9fdd3202ca2 | 1063 | pc.printf("4) Move Arm Down\r\n"); |
Vigilance88 | 30:a9fdd3202ca2 | 1064 | pc.printf("q) Exit \r\n"); |
Vigilance88 | 30:a9fdd3202ca2 | 1065 | pc.printf("Please make a choice => \r\n"); |
Vigilance88 | 30:a9fdd3202ca2 | 1066 | } |
Vigilance88 | 30:a9fdd3202ca2 | 1067 | |
Vigilance88 | 28:743485bb51e4 | 1068 | void caliMenu(){ |
Vigilance88 | 28:743485bb51e4 | 1069 | |
Vigilance88 | 28:743485bb51e4 | 1070 | //Title Box |
Vigilance88 | 28:743485bb51e4 | 1071 | pc.putc(201); |
Vigilance88 | 28:743485bb51e4 | 1072 | for(int j=0;j<33;j++){ |
Vigilance88 | 28:743485bb51e4 | 1073 | pc.putc(205); |
Vigilance88 | 28:743485bb51e4 | 1074 | } |
Vigilance88 | 28:743485bb51e4 | 1075 | pc.putc(187); |
Vigilance88 | 28:743485bb51e4 | 1076 | pc.printf("\n\r"); |
Vigilance88 | 28:743485bb51e4 | 1077 | pc.putc(186); pc.printf(" Calibration Menu "); pc.putc(186); |
Vigilance88 | 28:743485bb51e4 | 1078 | pc.printf("\n\r"); |
Vigilance88 | 28:743485bb51e4 | 1079 | pc.putc(200); |
Vigilance88 | 28:743485bb51e4 | 1080 | for(int k=0;k<33;k++){ |
Vigilance88 | 28:743485bb51e4 | 1081 | pc.putc(205); |
Vigilance88 | 28:743485bb51e4 | 1082 | } |
Vigilance88 | 28:743485bb51e4 | 1083 | pc.putc(188); |
Vigilance88 | 28:743485bb51e4 | 1084 | |
Vigilance88 | 28:743485bb51e4 | 1085 | pc.printf("\n\r"); |
Vigilance88 | 28:743485bb51e4 | 1086 | //endbox |
Vigilance88 | 28:743485bb51e4 | 1087 | |
Vigilance88 | 28:743485bb51e4 | 1088 | pc.printf("[A]rm Calibration\r\n"); |
Vigilance88 | 28:743485bb51e4 | 1089 | pc.printf("[E]MG Calibration\r\n"); |
Vigilance88 | 28:743485bb51e4 | 1090 | pc.printf("[B]ack to main menu\r\n"); |
Vigilance88 | 28:743485bb51e4 | 1091 | pc.printf("Please make a choice => \r\n"); |
Vigilance88 | 28:743485bb51e4 | 1092 | |
Vigilance88 | 28:743485bb51e4 | 1093 | } |
Vigilance88 | 28:743485bb51e4 | 1094 | |
Vigilance88 | 28:743485bb51e4 | 1095 | void titleBox(){ |
Vigilance88 | 28:743485bb51e4 | 1096 | |
Vigilance88 | 28:743485bb51e4 | 1097 | //Title Box |
Vigilance88 | 28:743485bb51e4 | 1098 | pc.putc(201); |
Vigilance88 | 28:743485bb51e4 | 1099 | for(int j=0;j<33;j++){ |
Vigilance88 | 28:743485bb51e4 | 1100 | pc.putc(205); |
Vigilance88 | 28:743485bb51e4 | 1101 | } |
Vigilance88 | 28:743485bb51e4 | 1102 | pc.putc(187); |
Vigilance88 | 28:743485bb51e4 | 1103 | pc.printf("\n\r"); |
Vigilance88 | 28:743485bb51e4 | 1104 | pc.putc(186); pc.printf(" BioRobotics M9 - Group 14 "); pc.putc(186); |
Vigilance88 | 28:743485bb51e4 | 1105 | pc.printf("\n\r"); |
Vigilance88 | 28:743485bb51e4 | 1106 | pc.putc(186); pc.printf(" Robot powered ON "); pc.putc(186); |
Vigilance88 | 28:743485bb51e4 | 1107 | pc.printf("\n\r"); |
Vigilance88 | 28:743485bb51e4 | 1108 | pc.putc(200); |
Vigilance88 | 28:743485bb51e4 | 1109 | for(int k=0;k<33;k++){ |
Vigilance88 | 28:743485bb51e4 | 1110 | pc.putc(205); |
Vigilance88 | 28:743485bb51e4 | 1111 | } |
Vigilance88 | 28:743485bb51e4 | 1112 | pc.putc(188); |
Vigilance88 | 28:743485bb51e4 | 1113 | |
Vigilance88 | 28:743485bb51e4 | 1114 | pc.printf("\n\r"); |
Vigilance88 | 28:743485bb51e4 | 1115 | //endbox |
Vigilance88 | 28:743485bb51e4 | 1116 | } |
Vigilance88 | 28:743485bb51e4 | 1117 | |
Vigilance88 | 28:743485bb51e4 | 1118 | void emgInstructions(){ |
Vigilance88 | 28:743485bb51e4 | 1119 | pc.printf("\r\nPrepare the skin before applying electrodes: \n\r"); wait(1); |
Vigilance88 | 28:743485bb51e4 | 1120 | pc.printf("-> Shave electrode locations if needed and clean with alcohol \n\r"); wait(1); |
Vigilance88 | 28:743485bb51e4 | 1121 | pc.printf("\n\r Relax for a few minutes after electrodes are placed and check if EMG signal looks normal \n\r "); wait(1); |
Vigilance88 | 28:743485bb51e4 | 1122 | pc.printf("\n\r To calibrate the EMG signals we will measure the Maximum Voluntary Contraction of each muscle \n\r"); wait(1); |
Vigilance88 | 28:743485bb51e4 | 1123 | pc.printf("You will need to flex the mentioned muscle as much as possible for 5 seconds \n\r"); wait(1); |
Vigilance88 | 28:743485bb51e4 | 1124 | pc.printf("The measurement will begin once you confirm you're ready [Hit any key] \n\r \n\r"); wait(1); |
Vigilance88 | 28:743485bb51e4 | 1125 | } |
Vigilance88 | 28:743485bb51e4 | 1126 | |
Vigilance88 | 21:d6a46315d5f5 | 1127 | //keeps input limited between min max |
Vigilance88 | 24:56db31267f10 | 1128 | void keep_in_range(double * in, double min, double max) |
Vigilance88 | 18:44905b008f44 | 1129 | { |
Vigilance88 | 18:44905b008f44 | 1130 | *in > min ? *in < max? : *in = max: *in = min; |
vsluiter | 0:32bb76391d89 | 1131 | } |