2nd draft

Dependencies:   HIDScope MODSERIAL QEI biquadFilter mbed Servo

Fork of robot_mockup by Martijn Kern

Committer:
Vigilance88
Date:
Thu Oct 22 14:18:41 2015 +0000
Revision:
35:7d9fca0b1545
Parent:
34:d6ec7c634763
Child:
36:4d4fc200171b
added minimum emg measurement to calibration

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