2nd draft

Dependencies:   HIDScope MODSERIAL QEI biquadFilter mbed Servo

Fork of robot_mockup by Martijn Kern

Committer:
Vigilance88
Date:
Fri Oct 30 08:00:09 2015 +0000
Revision:
63:08357f5c497b
Parent:
62:e400138d625e
Child:
64:21fbff25d80b
fixed some comments

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