2nd draft

Dependencies:   HIDScope MODSERIAL QEI biquadFilter mbed Servo

Fork of robot_mockup by Martijn Kern

Committer:
Vigilance88
Date:
Thu Oct 22 23:19:50 2015 +0000
Revision:
36:4d4fc200171b
Parent:
35:7d9fca0b1545
Child:
37:4d7b7ced20ef
DLS and Trig control loops work.

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