2nd draft

Dependencies:   HIDScope MODSERIAL QEI biquadFilter mbed Servo

Fork of robot_mockup by Martijn Kern

Committer:
Vigilance88
Date:
Tue Oct 27 10:11:29 2015 +0000
Revision:
54:4cda9af56bed
Parent:
53:bf0d97487e84
Child:
55:726fdab812a9
fixed servo

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