2nd draft

Dependencies:   HIDScope MODSERIAL QEI biquadFilter mbed Servo

Fork of robot_mockup by Martijn Kern

Committer:
Vigilance88
Date:
Fri Oct 23 09:33:28 2015 +0000
Revision:
42:b9d26b1218b0
Parent:
41:55face19e06b
Child:
44:145827f5b091
added error 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 42:b9d26b1218b0 271 pwm_motor1.period(0.001);
Vigilance88 42:b9d26b1218b0 272 pwm_motor2.period(0.001);
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 42:b9d26b1218b0 536
Vigilance88 32:76c4d7bb2022 537 }
Vigilance88 32:76c4d7bb2022 538
Vigilance88 18:44905b008f44 539 //Send arm to mechanical limits, and set encoder to 0. Then send arm to starting position.
Vigilance88 19:0a3ee31dcdb4 540 void calibrate_arm(void)
Vigilance88 19:0a3ee31dcdb4 541 {
Vigilance88 28:743485bb51e4 542 pc.printf("Calibrate_arm() entered\r\n");
Vigilance88 32:76c4d7bb2022 543 red=0; blue=0; //Debug light is purple during arm calibration
Vigilance88 32:76c4d7bb2022 544
Vigilance88 32:76c4d7bb2022 545 done1 = false;
Vigilance88 32:76c4d7bb2022 546 done2 = false;
Vigilance88 26:fe3a5469dd6b 547 bool calibrating = true;
Vigilance88 32:76c4d7bb2022 548
Vigilance88 27:d1814e271a95 549 pc.printf("To start arm calibration, press any key =>");
Vigilance88 27:d1814e271a95 550 pc.getc();
Vigilance88 27:d1814e271a95 551 pc.printf("\r\n Calibrating... \r\n");
Vigilance88 36:4d4fc200171b 552 dir_motor1=0; //cw
Vigilance88 36:4d4fc200171b 553 dir_motor2=1; //cw
Vigilance88 36:4d4fc200171b 554
Vigilance88 27:d1814e271a95 555
Vigilance88 26:fe3a5469dd6b 556
Vigilance88 26:fe3a5469dd6b 557 while(calibrating){
Vigilance88 32:76c4d7bb2022 558 shoulder_limit.rise(&shoulder);
Vigilance88 32:76c4d7bb2022 559 elbow_limit.rise(&elbow);
Vigilance88 36:4d4fc200171b 560 while(!done1){
Vigilance88 36:4d4fc200171b 561 pwm_motor1.write(0.2); //move upper arm slowly cw
Vigilance88 36:4d4fc200171b 562 }
Vigilance88 27:d1814e271a95 563 if(done1==true){
Vigilance88 27:d1814e271a95 564 pwm_motor2.write(0.2); //move forearm slowly cw
Vigilance88 27:d1814e271a95 565 }
Vigilance88 27:d1814e271a95 566
Vigilance88 26:fe3a5469dd6b 567 if(done1 && done2){
Vigilance88 26:fe3a5469dd6b 568 calibrating=false; //Leave while loop when both limits are reached
Vigilance88 26:fe3a5469dd6b 569 red=1; blue=1; //Turn debug light off when calibration complete
Vigilance88 26:fe3a5469dd6b 570 }
Vigilance88 27:d1814e271a95 571
Vigilance88 27:d1814e271a95 572 }//end while
Vigilance88 32:76c4d7bb2022 573
Vigilance88 27:d1814e271a95 574 //TO DO:
Vigilance88 36:4d4fc200171b 575
Vigilance88 27:d1814e271a95 576 //pc.printf("Elbow Limit hit - shutting down motor 2. Current pulsecount: %i \r\n",Encoder1.getPulses());
Vigilance88 31:7b8b8459bddc 577
Vigilance88 42:b9d26b1218b0 578 //set reference position to mechanical limits
Vigilance88 42:b9d26b1218b0 579 x = 0.2220;
Vigilance88 42:b9d26b1218b0 580 y = 0.4088;
Vigilance88 42:b9d26b1218b0 581
Vigilance88 27:d1814e271a95 582 wait(1);
Vigilance88 28:743485bb51e4 583 pc.printf("\n\r ------------------------ \n\r");
Vigilance88 27:d1814e271a95 584 pc.printf("Arm Calibration Complete\r\n");
Vigilance88 28:743485bb51e4 585 pc.printf(" ------------------------ \n\r");
Vigilance88 26:fe3a5469dd6b 586
Vigilance88 19:0a3ee31dcdb4 587 }
Vigilance88 19:0a3ee31dcdb4 588
Vigilance88 21:d6a46315d5f5 589 //EMG Maximum Voluntary Contraction measurement
Vigilance88 25:49ccdc98639a 590 void emg_mvc()
Vigilance88 25:49ccdc98639a 591 {
Vigilance88 24:56db31267f10 592 //double sampletime=0;
Vigilance88 24:56db31267f10 593 //sampletime=+SAMPLE_RATE;
Vigilance88 24:56db31267f10 594 //
Vigilance88 24:56db31267f10 595 // if(sampletime<5)
Vigilance88 25:49ccdc98639a 596 //int muscle=1;
Vigilance88 25:49ccdc98639a 597 //for(int index=0; index<2500;index++){ //measure 5 seconds@500hz = 2500 samples
Vigilance88 25:49ccdc98639a 598
Vigilance88 24:56db31267f10 599 if(muscle==1){
Vigilance88 24:56db31267f10 600
Vigilance88 24:56db31267f10 601 if(biceps_power>bicepsMVC){
Vigilance88 26:fe3a5469dd6b 602 //printf("+ ");
Vigilance88 26:fe3a5469dd6b 603 printf("%s+ %s",GREEN_,_GREEN);
Vigilance88 21:d6a46315d5f5 604 bicepsMVC=biceps_power;
Vigilance88 24:56db31267f10 605 }
Vigilance88 25:49ccdc98639a 606 else
Vigilance88 25:49ccdc98639a 607 printf("- ");
Vigilance88 24:56db31267f10 608 }
Vigilance88 24:56db31267f10 609
Vigilance88 24:56db31267f10 610 if(muscle==2){
Vigilance88 24:56db31267f10 611
Vigilance88 24:56db31267f10 612 if(triceps_power>tricepsMVC){
Vigilance88 26:fe3a5469dd6b 613 printf("%s+ %s",GREEN_,_GREEN);
Vigilance88 24:56db31267f10 614 tricepsMVC=triceps_power;
Vigilance88 24:56db31267f10 615 }
Vigilance88 26:fe3a5469dd6b 616 else
Vigilance88 26:fe3a5469dd6b 617 printf("- ");
Vigilance88 24:56db31267f10 618 }
Vigilance88 24:56db31267f10 619
Vigilance88 24:56db31267f10 620 if(muscle==3){
Vigilance88 24:56db31267f10 621
Vigilance88 24:56db31267f10 622 if(flexor_power>flexorMVC){
Vigilance88 26:fe3a5469dd6b 623 printf("%s+ %s",GREEN_,_GREEN);
Vigilance88 24:56db31267f10 624 flexorMVC=flexor_power;
Vigilance88 24:56db31267f10 625 }
Vigilance88 26:fe3a5469dd6b 626 else
Vigilance88 26:fe3a5469dd6b 627 printf("- ");
Vigilance88 24:56db31267f10 628 }
Vigilance88 24:56db31267f10 629
Vigilance88 24:56db31267f10 630 if(muscle==4){
Vigilance88 24:56db31267f10 631
Vigilance88 24:56db31267f10 632 if(extens_power>extensMVC){
Vigilance88 26:fe3a5469dd6b 633 printf("%s+ %s",GREEN_,_GREEN);
Vigilance88 24:56db31267f10 634 extensMVC=extens_power;
Vigilance88 24:56db31267f10 635 }
Vigilance88 26:fe3a5469dd6b 636 else
Vigilance88 26:fe3a5469dd6b 637 printf("- ");
Vigilance88 24:56db31267f10 638 }
Vigilance88 25:49ccdc98639a 639
Vigilance88 25:49ccdc98639a 640 //}
Vigilance88 25:49ccdc98639a 641 calibrate_time = calibrate_time + 0.002;
Vigilance88 36:4d4fc200171b 642
Vigilance88 25:49ccdc98639a 643 }
Vigilance88 25:49ccdc98639a 644
Vigilance88 35:7d9fca0b1545 645 void emg_min()
Vigilance88 35:7d9fca0b1545 646 {
Vigilance88 35:7d9fca0b1545 647
Vigilance88 38:c8ac615d0c8f 648 if(biceps_power>bicepsmin){
Vigilance88 35:7d9fca0b1545 649 bicepsmin=biceps_power;
Vigilance88 35:7d9fca0b1545 650 }
Vigilance88 35:7d9fca0b1545 651
Vigilance88 38:c8ac615d0c8f 652 if(triceps_power>tricepsmin){
Vigilance88 35:7d9fca0b1545 653 tricepsmin=triceps_power;
Vigilance88 35:7d9fca0b1545 654 }
Vigilance88 35:7d9fca0b1545 655
Vigilance88 38:c8ac615d0c8f 656 if(flexor_power>flexormin){
Vigilance88 35:7d9fca0b1545 657 flexormin=flexor_power;
Vigilance88 35:7d9fca0b1545 658 }
Vigilance88 35:7d9fca0b1545 659
Vigilance88 38:c8ac615d0c8f 660 if(extens_power > extensmin){
Vigilance88 35:7d9fca0b1545 661 extensmin = extens_power;
Vigilance88 35:7d9fca0b1545 662 }
Vigilance88 35:7d9fca0b1545 663
Vigilance88 35:7d9fca0b1545 664 calibrate_time = calibrate_time + 0.002;
Vigilance88 35:7d9fca0b1545 665
Vigilance88 35:7d9fca0b1545 666 }
Vigilance88 35:7d9fca0b1545 667
Vigilance88 25:49ccdc98639a 668 //EMG calibration
Vigilance88 25:49ccdc98639a 669 void calibrate_emg()
Vigilance88 25:49ccdc98639a 670 {
Vigilance88 25:49ccdc98639a 671 Ticker timer;
Vigilance88 25:49ccdc98639a 672
Vigilance88 38:c8ac615d0c8f 673 pc.printf("Starting sampling, to allow hidscope to normalize\r\n");
Vigilance88 38:c8ac615d0c8f 674 start_sampling();
Vigilance88 25:49ccdc98639a 675 wait(1);
Vigilance88 38:c8ac615d0c8f 676 pc.printf("Start minimum measurement, relax all muscles.\r\n");
Vigilance88 35:7d9fca0b1545 677 wait(1);
Vigilance88 35:7d9fca0b1545 678 pc.printf(" Press any key to begin... "); wait(1);
Vigilance88 35:7d9fca0b1545 679 char input;
Vigilance88 35:7d9fca0b1545 680 input=pc.getc();
Vigilance88 35:7d9fca0b1545 681 pc.printf(" \r\n Starting in 3... \r\n"); wait(1);
Vigilance88 35:7d9fca0b1545 682 pc.printf(" \r\n Starting in 2... \r\n"); wait(1);
Vigilance88 35:7d9fca0b1545 683 pc.printf(" \r\n Starting in 1... \r\n"); wait(1);
Vigilance88 35:7d9fca0b1545 684
Vigilance88 38:c8ac615d0c8f 685
Vigilance88 36:4d4fc200171b 686
Vigilance88 35:7d9fca0b1545 687 timer.attach(&emg_min,SAMPLE_RATE);
Vigilance88 35:7d9fca0b1545 688 wait(5);
Vigilance88 35:7d9fca0b1545 689 timer.detach();
Vigilance88 35:7d9fca0b1545 690 pc.printf("\r\n Measurement complete."); wait(1);
Vigilance88 35:7d9fca0b1545 691 pc.printf("\r\n Biceps min = %f \r\n",bicepsmin); wait(1);
Vigilance88 35:7d9fca0b1545 692 pc.printf("\r\n Triceps min = %f \r\n",tricepsmin); wait(1);
Vigilance88 35:7d9fca0b1545 693 pc.printf("\r\n Flexor min = %f \r\n",flexormin); wait(1);
Vigilance88 35:7d9fca0b1545 694 pc.printf("\r\n Extensor min = %f \r\n",extensmin); wait(1);
Vigilance88 35:7d9fca0b1545 695
Vigilance88 35:7d9fca0b1545 696 calibrate_time=0;
Vigilance88 35:7d9fca0b1545 697 pc.printf("\r\n Now we will measure maximum amplitudes \r\n"); wait(1);
Vigilance88 25:49ccdc98639a 698 pc.printf("+ means current sample is higher than stored MVC\r\n");
Vigilance88 25:49ccdc98639a 699 pc.printf("- means current sample is lower than stored MVC\r\n");
Vigilance88 26:fe3a5469dd6b 700 wait(2);
Vigilance88 28:743485bb51e4 701 pc.printf("\r\n----------------\r\n ");
Vigilance88 28:743485bb51e4 702 pc.printf(" Biceps is first.\r\n ");
Vigilance88 28:743485bb51e4 703 pc.printf("----------------\r\n ");
Vigilance88 28:743485bb51e4 704 wait(1);
Vigilance88 25:49ccdc98639a 705 pc.printf(" Press any key to begin... "); wait(1);
Vigilance88 25:49ccdc98639a 706 input=pc.getc();
Vigilance88 25:49ccdc98639a 707 pc.putc(input);
Vigilance88 25:49ccdc98639a 708 pc.printf(" \r\n Starting in 3... \r\n"); wait(1);
Vigilance88 25:49ccdc98639a 709 pc.printf(" \r\n Starting in 2... \r\n"); wait(1);
Vigilance88 25:49ccdc98639a 710 pc.printf(" \r\n Starting in 1... \r\n"); wait(1);
Vigilance88 25:49ccdc98639a 711
Vigilance88 25:49ccdc98639a 712 start_sampling();
Vigilance88 25:49ccdc98639a 713 muscle=1;
Vigilance88 27:d1814e271a95 714 timer.attach(&emg_mvc,SAMPLE_RATE);
Vigilance88 25:49ccdc98639a 715 wait(5);
Vigilance88 25:49ccdc98639a 716 timer.detach();
Vigilance88 26:fe3a5469dd6b 717
Vigilance88 26:fe3a5469dd6b 718 pc.printf("\r\n Measurement complete."); wait(1);
Vigilance88 26:fe3a5469dd6b 719 pc.printf("\r\n Biceps MVC = %f \r\n",bicepsMVC); wait(1);
Vigilance88 26:fe3a5469dd6b 720 pc.printf("Calibrate_emg() exited \r\n"); wait(1);
Vigilance88 26:fe3a5469dd6b 721 pc.printf("Measured time: %f seconds \r\n\n",calibrate_time);
Vigilance88 25:49ccdc98639a 722 calibrate_time=0;
Vigilance88 25:49ccdc98639a 723
Vigilance88 25:49ccdc98639a 724 // Triceps:
Vigilance88 26:fe3a5469dd6b 725 muscle=2;
Vigilance88 28:743485bb51e4 726 pc.printf("\r\n----------------\r\n ");
Vigilance88 28:743485bb51e4 727 pc.printf(" Triceps is next.\r\n ");
Vigilance88 28:743485bb51e4 728 pc.printf("----------------\r\n ");
Vigilance88 28:743485bb51e4 729 wait(1);
Vigilance88 28:743485bb51e4 730
Vigilance88 25:49ccdc98639a 731 pc.printf(" Press any key to begin... "); wait(1);
Vigilance88 25:49ccdc98639a 732 input=pc.getc();
Vigilance88 25:49ccdc98639a 733 pc.putc(input);
Vigilance88 25:49ccdc98639a 734 pc.printf(" \r\n Starting in 3... \r\n"); wait(1);
Vigilance88 25:49ccdc98639a 735 pc.printf(" \r\n Starting in 2... \r\n"); wait(1);
Vigilance88 25:49ccdc98639a 736 pc.printf(" \r\n Starting in 1... \r\n"); wait(1);
Vigilance88 25:49ccdc98639a 737 start_sampling();
Vigilance88 25:49ccdc98639a 738 timer.attach(&emg_mvc,0.002);
Vigilance88 25:49ccdc98639a 739 wait(5);
Vigilance88 25:49ccdc98639a 740 timer.detach();
Vigilance88 25:49ccdc98639a 741 pc.printf("\r\n Triceps MVC = %f \r\n",tricepsMVC);
Vigilance88 25:49ccdc98639a 742
Vigilance88 25:49ccdc98639a 743 pc.printf("Calibrate_emg() exited \r\n");
Vigilance88 25:49ccdc98639a 744 pc.printf("Measured time: %f seconds \r\n",calibrate_time);
Vigilance88 25:49ccdc98639a 745 calibrate_time=0;
Vigilance88 25:49ccdc98639a 746
Vigilance88 25:49ccdc98639a 747 //Flexor:
Vigilance88 26:fe3a5469dd6b 748 muscle=3;
Vigilance88 35:7d9fca0b1545 749 pc.printf("\r\n----------------\r\n ");
Vigilance88 35:7d9fca0b1545 750 pc.printf(" Flexor is next.\r\n ");
Vigilance88 35:7d9fca0b1545 751 pc.printf("----------------\r\n ");
Vigilance88 35:7d9fca0b1545 752 wait(1);
Vigilance88 35:7d9fca0b1545 753
Vigilance88 35:7d9fca0b1545 754 pc.printf(" Press any key to begin... "); wait(1);
Vigilance88 35:7d9fca0b1545 755 input=pc.getc();
Vigilance88 35:7d9fca0b1545 756 pc.putc(input);
Vigilance88 35:7d9fca0b1545 757 pc.printf(" \r\n Starting in 3... \r\n"); wait(1);
Vigilance88 35:7d9fca0b1545 758 pc.printf(" \r\n Starting in 2... \r\n"); wait(1);
Vigilance88 35:7d9fca0b1545 759 pc.printf(" \r\n Starting in 1... \r\n"); wait(1);
Vigilance88 35:7d9fca0b1545 760 start_sampling();
Vigilance88 35:7d9fca0b1545 761 timer.attach(&emg_mvc,0.002);
Vigilance88 35:7d9fca0b1545 762 wait(5);
Vigilance88 35:7d9fca0b1545 763 timer.detach();
Vigilance88 35:7d9fca0b1545 764 pc.printf("\r\n Flexor MVC = %f \r\n",flexorMVC);
Vigilance88 35:7d9fca0b1545 765
Vigilance88 35:7d9fca0b1545 766 pc.printf("Calibrate_emg() exited \r\n");
Vigilance88 35:7d9fca0b1545 767 pc.printf("Measured time: %f seconds \r\n",calibrate_time);
Vigilance88 35:7d9fca0b1545 768 calibrate_time=0;
Vigilance88 35:7d9fca0b1545 769
Vigilance88 25:49ccdc98639a 770 //Extensor:
Vigilance88 35:7d9fca0b1545 771
Vigilance88 26:fe3a5469dd6b 772 muscle=4;
Vigilance88 35:7d9fca0b1545 773 pc.printf("\r\n----------------\r\n ");
Vigilance88 35:7d9fca0b1545 774 pc.printf(" Extensor is next.\r\n ");
Vigilance88 35:7d9fca0b1545 775 pc.printf("----------------\r\n ");
Vigilance88 35:7d9fca0b1545 776 wait(1);
Vigilance88 35:7d9fca0b1545 777
Vigilance88 35:7d9fca0b1545 778 pc.printf(" Press any key to begin... "); wait(1);
Vigilance88 35:7d9fca0b1545 779 input=pc.getc();
Vigilance88 35:7d9fca0b1545 780 pc.putc(input);
Vigilance88 35:7d9fca0b1545 781 pc.printf(" \r\n Starting in 3... \r\n"); wait(1);
Vigilance88 35:7d9fca0b1545 782 pc.printf(" \r\n Starting in 2... \r\n"); wait(1);
Vigilance88 35:7d9fca0b1545 783 pc.printf(" \r\n Starting in 1... \r\n"); wait(1);
Vigilance88 35:7d9fca0b1545 784 start_sampling();
Vigilance88 35:7d9fca0b1545 785 timer.attach(&emg_mvc,0.002);
Vigilance88 35:7d9fca0b1545 786 wait(5);
Vigilance88 35:7d9fca0b1545 787 timer.detach();
Vigilance88 35:7d9fca0b1545 788 pc.printf("\r\n Extensor MVC = %f \r\n",extensMVC);
Vigilance88 25:49ccdc98639a 789
Vigilance88 35:7d9fca0b1545 790 pc.printf("Calibrate_emg() exited \r\n");
Vigilance88 35:7d9fca0b1545 791 pc.printf("Measured time: %f seconds \r\n",calibrate_time);
Vigilance88 35:7d9fca0b1545 792 calibrate_time=0;
Vigilance88 26:fe3a5469dd6b 793 //Stop sampling, detach ticker
Vigilance88 25:49ccdc98639a 794 stop_sampling();
Vigilance88 24:56db31267f10 795
Vigilance88 18:44905b008f44 796 }
Vigilance88 18:44905b008f44 797
Vigilance88 18:44905b008f44 798
Vigilance88 18:44905b008f44 799 //Input error and Kp, Kd, Ki, output control signal
Vigilance88 20:0ede3818e08e 800 double pid(double error, double kp, double ki, double kd,double &e_int, double &e_prev)
vsluiter 2:e314bb3b2d99 801 {
Vigilance88 20:0ede3818e08e 802 // Derivative
Vigilance88 24:56db31267f10 803 double e_der = (error-e_prev)/ CONTROL_RATE;
Vigilance88 21:d6a46315d5f5 804 e_der = derfilter.step(e_der);
Vigilance88 21:d6a46315d5f5 805 e_prev = error;
Vigilance88 20:0ede3818e08e 806 // Integral
Vigilance88 24:56db31267f10 807 e_int = e_int + CONTROL_RATE * error;
Vigilance88 20:0ede3818e08e 808 // PID
Vigilance88 21:d6a46315d5f5 809 return kp*error + ki*e_int + kd * e_der;
Vigilance88 20:0ede3818e08e 810
Vigilance88 18:44905b008f44 811 }
Vigilance88 18:44905b008f44 812
Vigilance88 20:0ede3818e08e 813 //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 814 void control()
Vigilance88 39:e77f844d10d9 815 {
Vigilance88 39:e77f844d10d9 816 if(emg_control=true){
Vigilance88 39:e77f844d10d9 817 //TODO some idle time with static reference before EMG kicks in
Vigilance88 39:e77f844d10d9 818 //emg_control_time += CONTROL_RATE;
Vigilance88 39:e77f844d10d9 819 // if emg_control_time < 5 seconds, reference is x=0; y=0;
Vigilance88 41:55face19e06b 820
Vigilance88 30:a9fdd3202ca2 821 //normalize emg to value between 0-1
Vigilance88 38:c8ac615d0c8f 822 biceps = (biceps_power - bicepsmin) / (bicepsMVC - bicepsmin);
Vigilance88 38:c8ac615d0c8f 823 triceps = (triceps_power - tricepsmin) / (tricepsMVC - tricepsmin);
Vigilance88 38:c8ac615d0c8f 824 flexor = (flexor_power - flexormin) / (flexorMVC - flexormin);
Vigilance88 38:c8ac615d0c8f 825 extens = (extens_power - extensmin) / (extensMVC - extensmin);
Vigilance88 39:e77f844d10d9 826 //make sure values stay between 0-1 over time
Vigilance88 39:e77f844d10d9 827 keep_in_range(&biceps,0,1);
Vigilance88 39:e77f844d10d9 828 keep_in_range(&triceps,0,1);
Vigilance88 39:e77f844d10d9 829 keep_in_range(&flexor,0,1);
Vigilance88 39:e77f844d10d9 830 keep_in_range(&extens,0,1);
Vigilance88 39:e77f844d10d9 831
Vigilance88 38:c8ac615d0c8f 832
Vigilance88 38:c8ac615d0c8f 833 scope.set(2,biceps);
Vigilance88 38:c8ac615d0c8f 834 scope.set(3,triceps);
Vigilance88 38:c8ac615d0c8f 835 scope.send();
Vigilance88 38:c8ac615d0c8f 836
Vigilance88 30:a9fdd3202ca2 837
Vigilance88 40:d62f96ed44c0 838 //threshold detection! buffer or two thresholds?
Vigilance88 39:e77f844d10d9 839 //TODO
Vigilance88 32:76c4d7bb2022 840
Vigilance88 39:e77f844d10d9 841 //analyze emg (= velocity)
Vigilance88 39:e77f844d10d9 842 if (biceps>triceps && biceps > 0.2){
Vigilance88 30:a9fdd3202ca2 843 xdir = 0;
Vigilance88 39:e77f844d10d9 844 xpower = biceps;}
Vigilance88 39:e77f844d10d9 845 else if (triceps>biceps && triceps>0.2){
Vigilance88 30:a9fdd3202ca2 846 xdir = 1;
Vigilance88 39:e77f844d10d9 847 xpower = triceps;}
Vigilance88 30:a9fdd3202ca2 848 else
Vigilance88 30:a9fdd3202ca2 849 xpower=0;
Vigilance88 30:a9fdd3202ca2 850
Vigilance88 39:e77f844d10d9 851 if (flexor>extens && flexor > 0.2){
Vigilance88 30:a9fdd3202ca2 852 ydir = 0;
Vigilance88 30:a9fdd3202ca2 853 ypower = flexor;
Vigilance88 30:a9fdd3202ca2 854 }
Vigilance88 39:e77f844d10d9 855 else if (extens>flexor && extens > 0.2){
Vigilance88 30:a9fdd3202ca2 856 ydir = 1;
Vigilance88 39:e77f844d10d9 857 ypower = extens;
Vigilance88 30:a9fdd3202ca2 858 }
Vigilance88 30:a9fdd3202ca2 859 else
Vigilance88 30:a9fdd3202ca2 860 ypower = 0;
Vigilance88 30:a9fdd3202ca2 861
Vigilance88 38:c8ac615d0c8f 862 //power: the longer a signal is active, the further the reference goes. So integrate to determine reference position
Vigilance88 39:e77f844d10d9 863 dx = xpower * CONTROL_RATE * 0.1; //factor to slow or speed up
Vigilance88 39:e77f844d10d9 864 dy = ypower * CONTROL_RATE * 0.1;
Vigilance88 18:44905b008f44 865
Vigilance88 30:a9fdd3202ca2 866 //But: direction! Sum dx and dy but make sure xdir and ydir are considered.
Vigilance88 30:a9fdd3202ca2 867 if (xdir>0)
Vigilance88 30:a9fdd3202ca2 868 x += dx;
Vigilance88 30:a9fdd3202ca2 869 else
Vigilance88 30:a9fdd3202ca2 870 x += -dx;
Vigilance88 30:a9fdd3202ca2 871
Vigilance88 30:a9fdd3202ca2 872 if (ydir>0)
Vigilance88 30:a9fdd3202ca2 873 y += dy;
Vigilance88 30:a9fdd3202ca2 874 else
Vigilance88 30:a9fdd3202ca2 875 y += -dy;
Vigilance88 30:a9fdd3202ca2 876
Vigilance88 39:e77f844d10d9 877 //now we have x and y -> reference position.
Vigilance88 39:e77f844d10d9 878 }//end emg_control if
Vigilance88 30:a9fdd3202ca2 879
Vigilance88 27:d1814e271a95 880 //Current position - Encoder counts -> current angle -> Forward Kinematics
Vigilance88 27:d1814e271a95 881 rpc=(2*PI)/ENCODER1_CPR; //radians per count (resolution) - 2pi divided by 4200
Vigilance88 27:d1814e271a95 882 theta1 = Encoder1.getPulses() * rpc; //multiply resolution with number of counts
Vigilance88 27:d1814e271a95 883 theta2 = Encoder2.getPulses() * rpc;
Vigilance88 27:d1814e271a95 884 current_x = l1 * cos(theta1) + l2 * cos(theta1 + theta2);
Vigilance88 27:d1814e271a95 885 current_y = l1 * sin(theta1) + l2 * sin(theta1 + theta2);
Vigilance88 27:d1814e271a95 886
Vigilance88 27:d1814e271a95 887
Vigilance88 18:44905b008f44 888 //calculate error (refpos-currentpos) currentpos = forward kinematics
Vigilance88 27:d1814e271a95 889 x_error = x - current_x;
Vigilance88 27:d1814e271a95 890 y_error = y - current_y;
Vigilance88 27:d1814e271a95 891
Vigilance88 27:d1814e271a95 892
Vigilance88 38:c8ac615d0c8f 893 if (control_method==1){
Vigilance88 27:d1814e271a95 894 //inverse kinematics (refpos to refangle)
Vigilance88 18:44905b008f44 895
Vigilance88 27:d1814e271a95 896 costheta2 = (pow(x,2) + pow(y,2) - pow(l1,2) - pow(l2,2)) / (2*l1*l2) ;
Vigilance88 30:a9fdd3202ca2 897 sintheta2 = sqrt( abs( 1 - pow(costheta2,2) ) );
Vigilance88 27:d1814e271a95 898
Vigilance88 27:d1814e271a95 899
Vigilance88 27:d1814e271a95 900 dtheta2 = atan2(sintheta2,costheta2);
Vigilance88 27:d1814e271a95 901
Vigilance88 32:76c4d7bb2022 902 double k1 = l1 + l2*costheta2;
Vigilance88 32:76c4d7bb2022 903 double k2 = l2*sintheta2;
Vigilance88 32:76c4d7bb2022 904
Vigilance88 32:76c4d7bb2022 905 dtheta1 = atan2(y, x) - atan2(k2, k1);
Vigilance88 32:76c4d7bb2022 906
Vigilance88 32:76c4d7bb2022 907 /* alternative:
Vigilance88 27:d1814e271a95 908 costheta1 = ( x * (l1 + l2 * costheta2) + y * l2 * sintheta2 ) / ( pow(x,2) + pow(y,2) );
Vigilance88 30:a9fdd3202ca2 909 sintheta1 = sqrt( abs( 1 - pow(costheta1,2) ) );
Vigilance88 27:d1814e271a95 910
Vigilance88 27:d1814e271a95 911 dtheta1 = atan2(sintheta1,costheta1);
Vigilance88 32:76c4d7bb2022 912 */
Vigilance88 27:d1814e271a95 913
Vigilance88 27:d1814e271a95 914 //Angle error
Vigilance88 27:d1814e271a95 915 m1_error = dtheta1-theta1;
Vigilance88 27:d1814e271a95 916 m2_error = dtheta2-theta2;
Vigilance88 39:e77f844d10d9 917 }// end control method 1
Vigilance88 27:d1814e271a95 918
Vigilance88 38:c8ac615d0c8f 919 if(control_method==2){
Vigilance88 37:4d7b7ced20ef 920 //inverse kinematics (error in position to error in angles)
Vigilance88 37:4d7b7ced20ef 921 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 922 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 923 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 924 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 925
Vigilance88 37:4d7b7ced20ef 926 q1_error = dls1 * x_error + dls2 * y_error;
Vigilance88 37:4d7b7ced20ef 927 q2_error = dls3 * x_error + dls4 * y_error;
Vigilance88 37:4d7b7ced20ef 928
Vigilance88 37:4d7b7ced20ef 929 //Angle error
Vigilance88 37:4d7b7ced20ef 930 m1_error = q1_error;
Vigilance88 37:4d7b7ced20ef 931 m2_error = q2_error;
Vigilance88 39:e77f844d10d9 932 }//end control method 2
Vigilance88 39:e77f844d10d9 933
Vigilance88 41:55face19e06b 934 /*
Vigilance88 39:e77f844d10d9 935 //Set limits to the error!
Vigilance88 41:55face19e06b 936 motor1: lower limit 40 degrees, upper limit 135
Vigilance88 41:55face19e06b 937 motor2: lower 43 degrees, upper limit 138 degrees. */
Vigilance88 41:55face19e06b 938
Vigilance88 41:55face19e06b 939 //lower limits: Negative error not allowed to go further.
Vigilance88 41:55face19e06b 940 if (theta1 < theta1_lower){
Vigilance88 41:55face19e06b 941 if (m1_error > 0)
Vigilance88 41:55face19e06b 942 m1_error = m1_error;
Vigilance88 39:e77f844d10d9 943 else
Vigilance88 41:55face19e06b 944 m1_error = 0; }
Vigilance88 41:55face19e06b 945 if (theta2 < theta2_lower){
Vigilance88 41:55face19e06b 946 if (m2_error > 0)
Vigilance88 41:55face19e06b 947 m2_error = m2_error;
Vigilance88 41:55face19e06b 948 else
Vigilance88 41:55face19e06b 949 m2_error = 0;
Vigilance88 41:55face19e06b 950 }
Vigilance88 39:e77f844d10d9 951 //upper limit: Positive error not allowed to go further
Vigilance88 41:55face19e06b 952 if (theta1 > theta1_upper){
Vigilance88 41:55face19e06b 953 if (m1_error < 0 )
Vigilance88 41:55face19e06b 954 m1_error = m1_error;
Vigilance88 39:e77f844d10d9 955 else
Vigilance88 41:55face19e06b 956 m1_error = 0;
Vigilance88 41:55face19e06b 957 }
Vigilance88 41:55face19e06b 958 if (theta2 > theta2_upper){
Vigilance88 41:55face19e06b 959 if (m2_error < 0 )
Vigilance88 41:55face19e06b 960 m2_error = m2_error;
Vigilance88 41:55face19e06b 961 else
Vigilance88 41:55face19e06b 962 m2_error = 0;
Vigilance88 41:55face19e06b 963 }
Vigilance88 39:e77f844d10d9 964
Vigilance88 18:44905b008f44 965 //PID controller
Vigilance88 24:56db31267f10 966
Vigilance88 24:56db31267f10 967 u1=pid(m1_error,m1_kp,m1_ki,m1_kd,m1_e_int,m1_e_prev); //motor 1
Vigilance88 24:56db31267f10 968 u2=pid(m2_error,m2_kp,m2_ki,m2_kd,m2_e_int,m2_e_prev); //motor 2
Vigilance88 21:d6a46315d5f5 969
Vigilance88 27:d1814e271a95 970 keep_in_range(&u1,-0.6,0.6); //keep u between -1 and 1, sign = direction, PWM = 0-1
Vigilance88 27:d1814e271a95 971 keep_in_range(&u2,-0.6,0.6);
Vigilance88 21:d6a46315d5f5 972
Vigilance88 21:d6a46315d5f5 973 //send PWM and DIR to motor 1
Vigilance88 21:d6a46315d5f5 974 dir_motor1 = u1>0 ? 1 : 0; //conditional statement dir_motor1 = [condition] ? [if met 1] : [else 0]], same as if else below.
Vigilance88 21:d6a46315d5f5 975 pwm_motor1.write(abs(u1));
Vigilance88 21:d6a46315d5f5 976
Vigilance88 21:d6a46315d5f5 977 //send PWM and DIR to motor 2
Vigilance88 27:d1814e271a95 978 dir_motor2 = u2>0 ? 0 : 1; //conditional statement, same as if else below
Vigilance88 25:49ccdc98639a 979 pwm_motor2.write(abs(u2));
Vigilance88 21:d6a46315d5f5 980
Vigilance88 21:d6a46315d5f5 981 /*if(u1 > 0)
Vigilance88 21:d6a46315d5f5 982 {
Vigilance88 21:d6a46315d5f5 983 dir_motor1 = 0;
Vigilance88 21:d6a46315d5f5 984 else{
Vigilance88 21:d6a46315d5f5 985 dir_motor1 = 1;
Vigilance88 21:d6a46315d5f5 986 }
Vigilance88 21:d6a46315d5f5 987 }
Vigilance88 21:d6a46315d5f5 988 pwm_motor1.write(abs(u1));
Vigilance88 21:d6a46315d5f5 989
Vigilance88 21:d6a46315d5f5 990
Vigilance88 21:d6a46315d5f5 991 if(u2 > 0)
Vigilance88 21:d6a46315d5f5 992 {
Vigilance88 21:d6a46315d5f5 993 dir_motor1 = 1;
Vigilance88 21:d6a46315d5f5 994 else{
Vigilance88 21:d6a46315d5f5 995 dir_motor1 = 0;
Vigilance88 21:d6a46315d5f5 996 }
Vigilance88 21:d6a46315d5f5 997 }
Vigilance88 21:d6a46315d5f5 998 pwm_motor1.write(abs(u2));*/
Vigilance88 21:d6a46315d5f5 999
Vigilance88 18:44905b008f44 1000 }
Vigilance88 18:44905b008f44 1001
Vigilance88 38:c8ac615d0c8f 1002
Vigilance88 32:76c4d7bb2022 1003
Vigilance88 26:fe3a5469dd6b 1004 void mainMenu()
Vigilance88 26:fe3a5469dd6b 1005 {
Vigilance88 38:c8ac615d0c8f 1006 //Title Box
Vigilance88 26:fe3a5469dd6b 1007 pc.putc(201);
Vigilance88 26:fe3a5469dd6b 1008 for(int j=0;j<33;j++){
Vigilance88 26:fe3a5469dd6b 1009 pc.putc(205);
Vigilance88 26:fe3a5469dd6b 1010 }
Vigilance88 26:fe3a5469dd6b 1011 pc.putc(187);
Vigilance88 26:fe3a5469dd6b 1012 pc.printf("\n\r");
Vigilance88 28:743485bb51e4 1013 pc.putc(186); pc.printf(" Main Menu "); pc.putc(186);
Vigilance88 26:fe3a5469dd6b 1014 pc.printf("\n\r");
Vigilance88 26:fe3a5469dd6b 1015 pc.putc(200);
Vigilance88 26:fe3a5469dd6b 1016 for(int k=0;k<33;k++){
Vigilance88 26:fe3a5469dd6b 1017 pc.putc(205);
Vigilance88 26:fe3a5469dd6b 1018 }
Vigilance88 26:fe3a5469dd6b 1019 pc.putc(188);
Vigilance88 26:fe3a5469dd6b 1020
Vigilance88 26:fe3a5469dd6b 1021 pc.printf("\n\r");
Vigilance88 26:fe3a5469dd6b 1022 //endbox
Vigilance88 28:743485bb51e4 1023 wait(1);
Vigilance88 28:743485bb51e4 1024 pc.printf("[C]alibration\r\n"); wait(0.2);
Vigilance88 40:d62f96ed44c0 1025 pc.printf("[T]RIG Control with WASD\r\n"); wait(0.2);
Vigilance88 40:d62f96ed44c0 1026 pc.printf("[D]LS Control with WASD\r\n"); wait(0.2);
Vigilance88 40:d62f96ed44c0 1027 pc.printf("[E]MG Control - DLS \r\n"); wait(0.2);
Vigilance88 28:743485bb51e4 1028 pc.printf("[Q]uit Robot Program\r\n"); wait(0.2);
Vigilance88 28:743485bb51e4 1029 pc.printf("[R]ed LED\r\n"); wait(0.2);
Vigilance88 28:743485bb51e4 1030 pc.printf("[G]reen LED\r\n"); wait(0.2);
Vigilance88 28:743485bb51e4 1031 pc.printf("[B]lue LED\r\n"); wait(0.2);
Vigilance88 28:743485bb51e4 1032 pc.printf("Please make a choice => \r\n");
Vigilance88 26:fe3a5469dd6b 1033 }
Vigilance88 24:56db31267f10 1034
Vigilance88 24:56db31267f10 1035 //Start sampling
Vigilance88 24:56db31267f10 1036 void start_sampling(void)
Vigilance88 24:56db31267f10 1037 {
Vigilance88 24:56db31267f10 1038 sample_timer.attach(&sample_filter,SAMPLE_RATE); //500 Hz EMG
Vigilance88 26:fe3a5469dd6b 1039
Vigilance88 26:fe3a5469dd6b 1040 //Debug LED will be green when sampling is active
Vigilance88 26:fe3a5469dd6b 1041 green=0;
Vigilance88 25:49ccdc98639a 1042 pc.printf("||- started sampling -|| \r\n");
Vigilance88 24:56db31267f10 1043 }
Vigilance88 24:56db31267f10 1044
Vigilance88 24:56db31267f10 1045 //stop sampling
Vigilance88 24:56db31267f10 1046 void stop_sampling(void)
Vigilance88 24:56db31267f10 1047 {
Vigilance88 24:56db31267f10 1048 sample_timer.detach();
Vigilance88 26:fe3a5469dd6b 1049
Vigilance88 26:fe3a5469dd6b 1050 //Debug LED will be turned off when sampling stops
Vigilance88 26:fe3a5469dd6b 1051 green=1;
Vigilance88 25:49ccdc98639a 1052 pc.printf("||- stopped sampling -|| \r\n");
Vigilance88 24:56db31267f10 1053 }
Vigilance88 24:56db31267f10 1054
Vigilance88 18:44905b008f44 1055 //Start control
Vigilance88 18:44905b008f44 1056 void start_control(void)
Vigilance88 18:44905b008f44 1057 {
Vigilance88 35:7d9fca0b1545 1058 control_timer.attach(&control,CONTROL_RATE); //100 Hz control
Vigilance88 35:7d9fca0b1545 1059
Vigilance88 35:7d9fca0b1545 1060 //Debug LED will be blue when control is on. If sampling and control are on -> blue + green = cyan.
Vigilance88 35:7d9fca0b1545 1061 blue=0;
Vigilance88 35:7d9fca0b1545 1062 pc.printf("||- started control -|| \r\n");
Vigilance88 35:7d9fca0b1545 1063 }
Vigilance88 35:7d9fca0b1545 1064
Vigilance88 18:44905b008f44 1065 //stop control
Vigilance88 18:44905b008f44 1066 void stop_control(void)
Vigilance88 18:44905b008f44 1067 {
Vigilance88 18:44905b008f44 1068 control_timer.detach();
Vigilance88 26:fe3a5469dd6b 1069
Vigilance88 26:fe3a5469dd6b 1070 //Debug LED will be off when control is off
Vigilance88 26:fe3a5469dd6b 1071 blue=1;
Vigilance88 26:fe3a5469dd6b 1072 pc.printf("||- stopped control -|| \r\n");
vsluiter 2:e314bb3b2d99 1073 }
vsluiter 0:32bb76391d89 1074
Vigilance88 21:d6a46315d5f5 1075
Vigilance88 26:fe3a5469dd6b 1076 //Clears the putty (or other terminal) window
Vigilance88 26:fe3a5469dd6b 1077 void clearTerminal()
Vigilance88 26:fe3a5469dd6b 1078 {
Vigilance88 26:fe3a5469dd6b 1079 pc.putc(27);
Vigilance88 26:fe3a5469dd6b 1080 pc.printf("[2J"); // clear screen
Vigilance88 26:fe3a5469dd6b 1081 pc.putc(27); // ESC
Vigilance88 26:fe3a5469dd6b 1082 pc.printf("[H"); // cursor to home
Vigilance88 26:fe3a5469dd6b 1083 }
Vigilance88 21:d6a46315d5f5 1084
Vigilance88 30:a9fdd3202ca2 1085
Vigilance88 30:a9fdd3202ca2 1086 void controlMenu()
Vigilance88 30:a9fdd3202ca2 1087 {
Vigilance88 30:a9fdd3202ca2 1088 //Title Box
Vigilance88 30:a9fdd3202ca2 1089 pc.putc(201);
Vigilance88 30:a9fdd3202ca2 1090 for(int j=0;j<33;j++){
Vigilance88 30:a9fdd3202ca2 1091 pc.putc(205);
Vigilance88 30:a9fdd3202ca2 1092 }
Vigilance88 30:a9fdd3202ca2 1093 pc.putc(187);
Vigilance88 30:a9fdd3202ca2 1094 pc.printf("\n\r");
Vigilance88 30:a9fdd3202ca2 1095 pc.putc(186); pc.printf(" Control Menu "); pc.putc(186);
Vigilance88 30:a9fdd3202ca2 1096 pc.printf("\n\r");
Vigilance88 30:a9fdd3202ca2 1097 pc.putc(200);
Vigilance88 30:a9fdd3202ca2 1098 for(int k=0;k<33;k++){
Vigilance88 30:a9fdd3202ca2 1099 pc.putc(205);
Vigilance88 30:a9fdd3202ca2 1100 }
Vigilance88 30:a9fdd3202ca2 1101 pc.putc(188);
Vigilance88 30:a9fdd3202ca2 1102
Vigilance88 30:a9fdd3202ca2 1103 pc.printf("\n\r");
Vigilance88 30:a9fdd3202ca2 1104 //endbox
Vigilance88 38:c8ac615d0c8f 1105 pc.printf("A) Move Arm Left\r\n");
Vigilance88 38:c8ac615d0c8f 1106 pc.printf("D) Move Arm Right\r\n");
Vigilance88 38:c8ac615d0c8f 1107 pc.printf("W) Move Arm Up\r\n");
Vigilance88 38:c8ac615d0c8f 1108 pc.printf("S) Move Arm Down\r\n");
Vigilance88 30:a9fdd3202ca2 1109 pc.printf("q) Exit \r\n");
Vigilance88 30:a9fdd3202ca2 1110 pc.printf("Please make a choice => \r\n");
Vigilance88 30:a9fdd3202ca2 1111 }
Vigilance88 30:a9fdd3202ca2 1112
Vigilance88 28:743485bb51e4 1113 void caliMenu(){
Vigilance88 28:743485bb51e4 1114
Vigilance88 28:743485bb51e4 1115 //Title Box
Vigilance88 28:743485bb51e4 1116 pc.putc(201);
Vigilance88 28:743485bb51e4 1117 for(int j=0;j<33;j++){
Vigilance88 28:743485bb51e4 1118 pc.putc(205);
Vigilance88 28:743485bb51e4 1119 }
Vigilance88 28:743485bb51e4 1120 pc.putc(187);
Vigilance88 28:743485bb51e4 1121 pc.printf("\n\r");
Vigilance88 28:743485bb51e4 1122 pc.putc(186); pc.printf(" Calibration Menu "); pc.putc(186);
Vigilance88 28:743485bb51e4 1123 pc.printf("\n\r");
Vigilance88 28:743485bb51e4 1124 pc.putc(200);
Vigilance88 28:743485bb51e4 1125 for(int k=0;k<33;k++){
Vigilance88 28:743485bb51e4 1126 pc.putc(205);
Vigilance88 28:743485bb51e4 1127 }
Vigilance88 28:743485bb51e4 1128 pc.putc(188);
Vigilance88 28:743485bb51e4 1129
Vigilance88 28:743485bb51e4 1130 pc.printf("\n\r");
Vigilance88 28:743485bb51e4 1131 //endbox
Vigilance88 28:743485bb51e4 1132
Vigilance88 28:743485bb51e4 1133 pc.printf("[A]rm Calibration\r\n");
Vigilance88 28:743485bb51e4 1134 pc.printf("[E]MG Calibration\r\n");
Vigilance88 28:743485bb51e4 1135 pc.printf("[B]ack to main menu\r\n");
Vigilance88 28:743485bb51e4 1136 pc.printf("Please make a choice => \r\n");
Vigilance88 28:743485bb51e4 1137
Vigilance88 28:743485bb51e4 1138 }
Vigilance88 28:743485bb51e4 1139
Vigilance88 28:743485bb51e4 1140 void titleBox(){
Vigilance88 28:743485bb51e4 1141
Vigilance88 28:743485bb51e4 1142 //Title Box
Vigilance88 28:743485bb51e4 1143 pc.putc(201);
Vigilance88 28:743485bb51e4 1144 for(int j=0;j<33;j++){
Vigilance88 28:743485bb51e4 1145 pc.putc(205);
Vigilance88 28:743485bb51e4 1146 }
Vigilance88 28:743485bb51e4 1147 pc.putc(187);
Vigilance88 28:743485bb51e4 1148 pc.printf("\n\r");
Vigilance88 28:743485bb51e4 1149 pc.putc(186); pc.printf(" BioRobotics M9 - Group 14 "); pc.putc(186);
Vigilance88 28:743485bb51e4 1150 pc.printf("\n\r");
Vigilance88 28:743485bb51e4 1151 pc.putc(186); pc.printf(" Robot powered ON "); pc.putc(186);
Vigilance88 28:743485bb51e4 1152 pc.printf("\n\r");
Vigilance88 28:743485bb51e4 1153 pc.putc(200);
Vigilance88 28:743485bb51e4 1154 for(int k=0;k<33;k++){
Vigilance88 28:743485bb51e4 1155 pc.putc(205);
Vigilance88 28:743485bb51e4 1156 }
Vigilance88 28:743485bb51e4 1157 pc.putc(188);
Vigilance88 28:743485bb51e4 1158
Vigilance88 28:743485bb51e4 1159 pc.printf("\n\r");
Vigilance88 28:743485bb51e4 1160 //endbox
Vigilance88 28:743485bb51e4 1161 }
Vigilance88 28:743485bb51e4 1162
Vigilance88 28:743485bb51e4 1163 void emgInstructions(){
Vigilance88 36:4d4fc200171b 1164 pc.printf("\r\nPrepare the skin before applying electrodes: \n\r");
Vigilance88 28:743485bb51e4 1165 pc.printf("-> Shave electrode locations if needed and clean with alcohol \n\r"); wait(1);
Vigilance88 38:c8ac615d0c8f 1166 pc.printf("\r\n Check whether EMG signal looks normal. \n\r "); wait(1);
Vigilance88 38:c8ac615d0c8f 1167 pc.printf("\r\n To calibrate the EMG signals we will measure: \n\r ");
Vigilance88 38:c8ac615d0c8f 1168 pc.printf("- Minimum amplitude, while relaxing all muscles. \n\r ");
Vigilance88 38:c8ac615d0c8f 1169 pc.printf("- Maximum Voluntary Contraction of each muscle. \n\r"); wait(2);
Vigilance88 38:c8ac615d0c8f 1170 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 1171 pc.printf("The measurements will begin once you confirm you're ready [Hit any key] \n\r \n\r"); wait(1);
Vigilance88 28:743485bb51e4 1172 }
Vigilance88 28:743485bb51e4 1173
Vigilance88 21:d6a46315d5f5 1174 //keeps input limited between min max
Vigilance88 24:56db31267f10 1175 void keep_in_range(double * in, double min, double max)
Vigilance88 18:44905b008f44 1176 {
Vigilance88 18:44905b008f44 1177 *in > min ? *in < max? : *in = max: *in = min;
vsluiter 0:32bb76391d89 1178 }