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