2nd draft
Dependencies: HIDScope MODSERIAL QEI biquadFilter mbed Servo
Fork of robot_mockup by
main.cpp
- Committer:
- Vigilance88
- Date:
- 2015-10-14
- Revision:
- 24:56db31267f10
- Parent:
- 23:e9b1b426cde6
- Child:
- 25:49ccdc98639a
File content as of revision 24:56db31267f10:
#include "mbed.h" #include "HIDScope.h" #include "MODSERIAL.h" #include "biquadFilter.h" #include "QEI.h" #include "math.h" /*-------------------------------------------------------------------------------------------------------------------- -------------------------------- BIOROBOTICS GROUP 14 ---------------------------------------------------------------- --------------------------------------------------------------------------------------------------------------------*/ //Define important constants in memory #define PI 3.14159265 #define SAMPLE_RATE 0.002 //500 Hz EMG sample rate #define CONTROL_RATE 0.01 //100 Hz Control rate #define ENCODER1_CPR 4200 //encoders have 64 (X4), 32 (X2) counts per revolution of motor shaft #define ENCODER2_CPR 4200 //gearbox 1:131.25 -> 4200 counts per revolution of the output shaft (X2), /*-------------------------------------------------------------------------------------------------------------------- ---- OBJECTS --------------------------------------------------------------------------------------------------------- --------------------------------------------------------------------------------------------------------------------*/ MODSERIAL pc(USBTX,USBRX); //serial communication DigitalIn button(PTA1); //buttons DigitalIn button1(PTB9); // //EMG shields AnalogIn emg1(A0); //Analog input - Biceps EMG AnalogIn emg2(A1); //Analog input - Triceps EMG AnalogIn emg3(A2); //Analog input - Flexor EMG AnalogIn emg4(A3); //Analog input - Extensor EMG Ticker sample_timer; //Ticker for EMG sampling Ticker control_timer; //Ticker for control loop HIDScope scope(4); //Scope 4 channels // AnalogIn potmeter(A4); //potmeters // AnalogIn potmeter2(A5); // //Encoders QEI Encoder1(D13,D12,NC,32); //channel A and B from encoder, counts = Encoder.getPulses(); QEI Encoder2(D10,D9,NC,32); //channel A and B from encoder, //Speed and Direction of motors - D4 (dir) and D5(speed) = motor 2, D7(dir) and D6(speed) = motor 1 PwmOut pwm_motor1(D6); //PWM motor 1 PwmOut pwm_motor2(D5); //PWM motor 2 DigitalOut dir_motor1(D7); //Direction motor 1 DigitalOut dir_motor2(D4); //Direction motor 2 //Limit Switches DigitalIn shoulder_limit(PTA4); //using FRDM buttons for now DigitalIn elbow_limit(PTC6); //using FRDM buttons for now /*-------------------------------------------------------------------------------------------------------------------- ---- DECLARE VARIABLES ----------------------------------------------------------------------------------------------- --------------------------------------------------------------------------------------------------------------------*/ //EMG variables double emg_biceps; double biceps_power; double bicepsMVC = 0; double emg_triceps; double triceps_power; double tricepsMVC = 0; double emg_flexor; double flexor_power; double flexorMVC = 0; double emg_extens; double extens_power; double extensMVC = 0; //PID variables double u1; double u2; //Output of PID controller (PWM value for motor 1 and 2) double m1_error=0; double m1_e_int=0; double m1_e_prev=0; //Error, integrated error, previous error const double m1_kp=0; const double m1_ki=0; const double m1_kd=0; //Proportional, integral and derivative gains. double m2_error=0; double m2_e_int=0; double m2_e_prev=0; //Error, integrated error, previous error const double m2_kp=0; const double m2_ki=0; const double m2_kd=0; //Proportional, integral and derivative gains. //highpass filter 20 Hz const double high_b0 = 0.956543225556877; const double high_b1 = -1.91308645113754; const double high_b2 = 0.956543225556877; const double high_a1 = -1.91197067426073; const double high_a2 = 0.9149758348014341; //notchfilter 50Hz /* ** Primary Filter (H1)** Filter Arithmetic = Floating Point (Double Precision) Architecture = IIR Response = Bandstop Method = Butterworth Biquad = Yes Stable = Yes Sampling Frequency = 500Hz Filter Order = 2 Band Frequencies (Hz) Att/Ripple (dB) Biquad #1 Biquad #2 1 0, 48 0.001 Gain = 1.000000 Gain = 0.973674 2 49, 51 -60.000 B = [ 1.00000000000, -1.61816176147, 1.00000000000] B = [ 1.00000000000, -1.61816176147, 1.00000000000] 3 52, 250 0.001 A = [ 1.00000000000, -1.58071559235, 0.97319685401] A = [ 1.00000000000, -1.61244708381, 0.97415116257] */ //biquad 1 const double notch1gain = 1.000000; const double notch1_b0 = 1; const double notch1_b1 = -1.61816176147 * notch1gain; const double notch1_b2 = 1.00000000000 * notch1gain; const double notch1_a1 = -1.58071559235 * notch1gain; const double notch1_a2 = 0.97319685401 * notch1gain; //biquad 2 const double notch2gain = 0.973674; const double notch2_b0 = 1 * notch2gain; const double notch2_b1 = -1.61816176147 * notch2gain; const double notch2_b2 = 1.00000000000 * notch2gain; const double notch2_a1 = -1.61244708381 * notch2gain; const double notch2_a2 = 0.97415116257 * notch2gain; //lowpass filter 7 Hz - envelop const double low_b0 = 0.000119046743110057; const double low_b1 = 0.000238093486220118; const double low_b2 = 0.000119046743110057; const double low_a1 = -1.968902268531908; const double low_a2 = 0.9693784555043481; /*-------------------------------------------------------------------------------------------------------------------- ---- Filters --------------------------------------------------------------------------------------------------------- --------------------------------------------------------------------------------------------------------------------*/ //Using biquadFilter library //Syntax: biquadFilter filter(a1, a2, b0, b1, b2); coefficients. Call with: filter.step(u), with u signal to be filtered. biquadFilter highpass( high_a1 , high_a2 , high_b0 , high_b1 , high_b2 ); // removes DC and movement artefacts biquadFilter notch1( notch1_a1 , notch1_a2 , notch1_b0 , notch1_b1 , notch1_b2 ); // removes 49-51 Hz power interference biquadFilter notch2( notch2_a1 , notch2_a2 , notch2_b0 , notch2_b1 , notch2_b2 ); // biquadFilter lowpass( low_a1 , low_a2 , low_b0 , low_b1 , low_b2 ); // EMG envelope biquadFilter derfilter( 0.0009446914586925257 , 0.0018893829173850514 , 0.0009446914586925257 , -1.911196288237583 , 0.914975054072353 ); // derivative filter /*-------------------------------------------------------------------------------------------------------------------- ---- DECLARE FUNCTION NAMES ------------------------------------------------------------------------------------------ --------------------------------------------------------------------------------------------------------------------*/ void keep_in_range(double * in, double min, double max); void sample_filter(void); void control(); void calibrate_emg(int muscle); void calibrate_arm(void); void start_sampling(void); void stop_sampling(void); void start_control(void); void stop_control(void); double pid(double error, double kp, double ki, double kd,double &e_int, double &e_prev); void mainMenu(); void caliMenu(); /*-------------------------------------------------------------------------------------------------------------------- ---- MAIN LOOP ------------------------------------------------------------------------------------------------------- --------------------------------------------------------------------------------------------------------------------*/ int main() { pc.baud(115200); // make a menu, user has to initiate next step mainMenu(); caliMenu(); // Menu function calibrate_arm(); //Start Calibration start_sampling(); //500 Hz EMG calibrate_emg(1); //calibrate muscle 1 start_control(); //100 Hz control //maybe some stop commands when a button is pressed: detach from timers. //stop_control(); //stop_sampling(); while(1) { scope.set(0,emg_biceps); scope.set(1,emg_triceps); scope.set(2,emg_flexor); scope.set(3,emg_extens); scope.send(); } //end of while loop } //end of main /*-------------------------------------------------------------------------------------------------------------------- ---- FUNCTIONS ------------------------------------------------------------------------------------------------------- --------------------------------------------------------------------------------------------------------------------*/ //Sample and Filter void sample_filter(void) { double emg_biceps = emg1.read(); //Biceps double emg_triceps = emg2.read(); //Triceps double emg_flexor = emg3.read(); //Flexor double emg_extens = emg4.read(); //Extensor //Filter: high-pass -> notch -> rectify -> lowpass or moving average // Can we use same biquadFilter (eg. highpass) for other muscles or does each muscle need its own biquad? biceps_power = highpass.step(emg_biceps); triceps_power = highpass.step(emg_triceps); flexor_power = highpass.step(emg_flexor); extens_power = highpass.step(emg_extens); biceps_power = notch1.step(biceps_power); triceps_power = notch1.step(triceps_power); flexor_power = notch1.step(flexor_power); extens_power = notch1.step(extens_power); biceps_power = notch2.step(biceps_power); triceps_power = notch2.step(triceps_power); flexor_power = notch2.step(flexor_power); extens_power = notch2.step(extens_power); biceps_power = abs(biceps_power); triceps_power = abs(triceps_power); flexor_power = abs(flexor_power); extens_power = abs(extens_power); biceps_power = lowpass.step(biceps_power); triceps_power = lowpass.step(triceps_power); flexor_power = lowpass.step(flexor_power); extens_power = lowpass.step(extens_power); /* alternative for lowpass filter: moving average window=30; //30 samples int i=0; //buffer index bicepsbuffer[i]=biceps_power //fill array i++; if(i==window){ i=0; } for(int x = 0; x < window; x++){ avg1 += bicepsbuffer[x]; } avg1 = avg1/window; */ } //Send arm to mechanical limits, and set encoder to 0. Then send arm to starting position. void calibrate_arm(void) { bool hit = true; dir_motor1=1; //ccw dir_motor2=1; //ccw while(shoulder_limit != hit){ pwm_motor1.write(0.4); } Encoder1.reset(); while(elbow_limit != hit){ pwm_motor2.write(0.4); } Encoder2.reset(); } //EMG Maximum Voluntary Contraction measurement void calibrate_emg(int muscle) { start_sampling(); //double sampletime=0; //sampletime=+SAMPLE_RATE; // // if(sampletime<5) for(int index=0; index<2500;index++){ //measure 5 seconds@500hz = 2500 samples if(muscle==1){ if(biceps_power>bicepsMVC){ bicepsMVC=biceps_power; } } if(muscle==2){ if(triceps_power>tricepsMVC){ tricepsMVC=triceps_power; } } if(muscle==3){ if(flexor_power>flexorMVC){ flexorMVC=flexor_power; } } if(muscle==4){ if(extens_power>extensMVC){ extensMVC=extens_power; } } } stop_sampling(); } //Input error and Kp, Kd, Ki, output control signal double pid(double error, double kp, double ki, double kd,double &e_int, double &e_prev) { // Derivative double e_der = (error-e_prev)/ CONTROL_RATE; e_der = derfilter.step(e_der); e_prev = error; // Integral e_int = e_int + CONTROL_RATE * error; // PID return kp*error + ki*e_int + kd * e_der; } //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 void control() { //analyze emg (= velocity, averages?) //calculate reference position based on the average emg (integrate) //calculate error (refpos-currentpos) currentpos = forward kinematics //inverse kinematics (pos error to angle error) //PID controller u1=pid(m1_error,m1_kp,m1_ki,m1_kd,m1_e_int,m1_e_prev); //motor 1 u2=pid(m2_error,m2_kp,m2_ki,m2_kd,m2_e_int,m2_e_prev); //motor 2 keep_in_range(&u1,-1,1); //keep u between -1 and 1, sign = direction, PWM = 0-1 keep_in_range(&u2,-1,1); //send PWM and DIR to motor 1 dir_motor1 = u1>0 ? 1 : 0; //conditional statement dir_motor1 = [condition] ? [if met 1] : [else 0]], same as if else below. pwm_motor1.write(abs(u1)); //send PWM and DIR to motor 2 dir_motor1 = u2>0 ? 1 : 0; //conditional statement, same as if else below pwm_motor1.write(abs(u2)); /*if(u1 > 0) { dir_motor1 = 0; else{ dir_motor1 = 1; } } pwm_motor1.write(abs(u1)); if(u2 > 0) { dir_motor1 = 1; else{ dir_motor1 = 0; } } pwm_motor1.write(abs(u2));*/ } void mainMenu(){}; void caliMenu(){}; //Start sampling void start_sampling(void) { sample_timer.attach(&sample_filter,SAMPLE_RATE); //500 Hz EMG } //stop sampling void stop_sampling(void) { sample_timer.detach(); } //Start control void start_control(void) { control_timer.attach(&control,CONTROL_RATE); //100 Hz control } //stop control void stop_control(void) { control_timer.detach(); } void calibrate() { } //keeps input limited between min max void keep_in_range(double * in, double min, double max) { *in > min ? *in < max? : *in = max: *in = min; }