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