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