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