2nd draft

Dependencies:   HIDScope MODSERIAL QEI biquadFilter mbed Servo

Fork of robot_mockup by Martijn Kern

Committer:
Vigilance88
Date:
Tue Oct 27 10:04:46 2015 +0000
Revision:
53:bf0d97487e84
Parent:
52:8a8c53dc8547
Child:
54:4cda9af56bed
added servo code.

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