2nd draft

Dependencies:   HIDScope MODSERIAL QEI biquadFilter mbed Servo

Fork of robot_mockup by Martijn Kern

Committer:
Vigilance88
Date:
Fri Oct 23 00:36:37 2015 +0000
Revision:
39:e77f844d10d9
Parent:
38:c8ac615d0c8f
Child:
40:d62f96ed44c0
added EMG reference calculation - needs lots of testing

Who changed what in which revision?

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