2nd draft

Dependencies:   HIDScope MODSERIAL QEI biquadFilter mbed Servo

Fork of robot_mockup by Martijn Kern

Committer:
Vigilance88
Date:
Fri Oct 23 09:14:22 2015 +0000
Revision:
41:55face19e06b
Parent:
40:d62f96ed44c0
Child:
42:b9d26b1218b0
added mechanical limits

Who changed what in which revision?

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