2nd draft

Dependencies:   HIDScope MODSERIAL QEI biquadFilter mbed Servo

Fork of robot_mockup by Martijn Kern

Committer:
Vigilance88
Date:
Fri Oct 23 14:07:58 2015 +0000
Revision:
46:c8c5c455dd51
Parent:
45:198654304238
Child:
47:c52f9b4c90c4
emg control werkt;

Who changed what in which revision?

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