De hele robot in 1 keer bam
Dependencies: mbed QEI Servo HIDScope biquadFilter MODSERIAL FastPWM
main.cpp
- Committer:
- BasB
- Date:
- 2019-10-31
- Revision:
- 47:63b5ccd969e9
- Parent:
- 46:8a8fa8e602a1
- Child:
- 48:31676da4be7a
File content as of revision 47:63b5ccd969e9:
/* ------------------------------ ADD LIBRARIES ------------------------------ */ #include "mbed.h" // Base library #include "HIDScope.h" // Scope connection to PC #include "MODSERIAL.h" // Serial connection to PC #include "BiQuad.h" // Biquad filter management #include <vector> // Array management #include "FastPWM.h" // PWM control #include "QEI.h" // Encoder reading #include <Servo.h> // Servo control /* ------------------------------ DEFINE MBED CONNECTIONS ------------------------------ */ // PC connections HIDScope scope( 6 ); MODSERIAL pc(USBTX, USBRX); // Buttons InterruptIn button1(D11); InterruptIn button2(D10); InterruptIn switch2(SW2); InterruptIn switch3(SW3); DigitalIn extButton1(D2); //Servo button // LEDs DigitalOut led_g(LED_GREEN); DigitalOut led_r(LED_RED); DigitalOut led_b(LED_BLUE); // Analog EMG inputs AnalogIn emg1_in (A0); // Right biceps -> x axis AnalogIn emg2_in (A1); // Left biceps -> y axis AnalogIn emg3_in (A2); // Third muscle -> TBD AnalogIn emg4_in (A3); // Third muscle -> TBD // Encoder inputs DigitalIn encA1(D9); DigitalIn encB1(D8); DigitalIn encA2(D13); DigitalIn encB2(D12); // Motor outputs DigitalOut motor1Direction(D7); FastPWM motor1Power(D6); DigitalOut motor2Direction(D4); FastPWM motor2Power(D5); // Servo Servo myservo(D3); bool butt1; /* ------------------------------ INITIALIZE TICKERS, TIMERS & TIMEOUTS ------------------------------ */ Ticker tickGlobal; // Set global ticker Timer timerCalibration; // Set EMG Calibration timer /* ------------------------------ INITIALIZE GLOBAL VARIABLES ------------------------------ */ // State machine variables enum GLOBAL_States { global_failure, global_wait, global_emg_cal, global_motor_cal, global_operation, global_demo }; // Define global states GLOBAL_States global_curr_state = global_wait; // Initialize global state to waiting state bool global_state_changed = true; // Enable entry functions bool failure_mode = false; // Global failure mode flag (not used yet) bool emg_cal_done = false; // Global EMG calibration flag bool motor_cal_done = false; // Global motor calibration flag // EMG Substate variables enum EMG_States { emg_wait, emg_cal_MVC, emg_cal_rest, emg_operation }; // Define EMG substates EMG_States emg_curr_state = emg_wait; // Initialize EMG substate variable bool emg_state_changed = true; // Enable entry functions bool emg_sampleNow = false; // Flag to enable EMG sampling and filtering in sampleSignals() bool emg_calibrateNow = false; // Flag to enable EMG calibration in sampleSignals() bool emg_MVC_cal_done = false; // Internal MVC calibration flag bool emg_rest_cal_done = false; // Internal rest calibration flag // Motor Substate variables enum Motor_States { motor_wait, motor_encoder_set, motor_finish, motor_movement }; // Define motor substates Motor_States motor_curr_state = motor_wait; // Initialize motor substate variable bool motor_state_changed = true; // Enable entry functions bool motor_encoder_cal_done = false; // Internal encoder calibration flag // Operation Substate variables enum Operation_States { operation_wait, operation_movement, operation_finish }; // Define operation substates Operation_States operation_curr_state = operation_wait; // Initialize operation substate variable bool operation_state_changed = true; // Enable entry functions bool operation_showcard = false; // Internal flag to toggle servo position // Demo Substate variables enum Demo_States { demo_wait, demo_motor_cal, demo_XY }; // Define demo substates Demo_States demo_curr_state; // Initialize demo substate variable bool demo_state_changed = true; // Enable entry functions // Button press interrupts (to prevent bounce) bool button1_pressed = false; bool button2_pressed = false; bool switch2_pressed = false; // Global constants const double Fs = 500.0; const double Ts = 1/Fs; /* ------------------------------ HELPER FUNCTIONS ------------------------------ */ // Empty placeholder function, needs to be deleted at end of project void doStuff() {} // Return max value of vector double getMax(const vector<double> &vect) { double curr_max = 0.0; int vect_n = vect.size(); for (int i = 0; i < vect_n; i++) { if (vect[i] > curr_max) { curr_max = vect[i]; }; } return curr_max; } // Return mean of vector double getMean(const vector<double> &vect) { double sum = 0.0; int vect_n = vect.size(); for ( int i = 0; i < vect_n; i++ ) { sum += vect[i]; } return sum/vect_n; } // Return standard deviation of vector double getStdev(const vector<double> &vect, const double vect_mean) { double sum2 = 0.0; int vect_n = vect.size(); for ( int i = 0; i < vect_n; i++ ) { sum2 += pow( vect[i] - vect_mean, 2 ); } double output = sqrt( sum2 / vect_n ); return output; } // Rescale double values to certain range double rescale(double input, double out_min, double out_max, double in_min, double in_max) { double output = out_min + ((input-in_min)/(in_max-in_min))*(out_max-out_min); // Based on MATLAB rescale function return output; } /* ------------------------------ BUTTON FUNCTIONS ------------------------------ */ // Handle button press void button1Press() { button1_pressed = true; } // Handle button press void button2Press() { button2_pressed = true; } void switch2Press() { switch2_pressed = true; } void switch3Press() { global_curr_state = global_failure; global_state_changed = true; } /* ------------------------------ EMG GLOBAL VARIABLES & CONSTANTS ------------------------------ */ // Set global constant values for EMG reading & analysis const double Tcal = 7.5f; // Calibration duration (s) // Initialize variables for EMG reading & analysis double emg1; double emg1_env; double emg1_MVC; double emg1_rest; double emg1_factor;//delete double emg1_th; double emg1_out; double emg1_norm; //delete vector<double> emg1_cal; int emg1_cal_size; //delete double emg1_dir = 1.0; double emg2; double emg2_env; double emg2_MVC; double emg2_rest; double emg2_factor;//delete double emg2_th; double emg2_out; double emg2_norm;//delete vector<double> emg2_cal; int emg2_cal_size;//delete double emg2_dir = 1.0; double emg3; double emg3_env; double emg3_MVC; double emg3_rest; double emg3_factor;//delete double emg3_th; double emg3_out; double emg3_norm;//delete vector<double> emg3_cal; double emg4; double emg4_env; double emg4_MVC; double emg4_rest; double emg4_factor;//delete double emg4_th; double emg4_out; double emg4_norm;//delete vector<double> emg4_cal; /* ------------------------------ EMG FILTERS ------------------------------ */ // Notch biquad filter coefficients (iirnotch Q factor 35 @50Hz) from MATLAB: BiQuad bq1_notch( 0.995636295063941, -1.89829218816065, 0.995636295063941, 1, -1.89829218816065, 0.991272590127882); // b01 b11 b21 a01 a11 a21 BiQuad bq2_notch = bq1_notch; BiQuad bq3_notch = bq1_notch; BiQuad bq4_notch = bq1_notch; BiQuadChain bqc1_notch; BiQuadChain bqc2_notch; BiQuadChain bqc3_notch; BiQuadChain bqc4_notch; // Highpass biquad filter coefficients (butter 4th order @10Hz cutoff) from MATLAB BiQuad bq1_H1(0.922946103200875, -1.84589220640175, 0.922946103200875, 1, -1.88920703055163, 0.892769008131025); // b01 b11 b21 a01 a11 a21 BiQuad bq1_H2(1, -2, 1, 1, -1.95046575793011, 0.954143234875078); // b02 b12 b22 a02 a12 a22 BiQuad bq2_H1 = bq1_H1; BiQuad bq2_H2 = bq1_H2; BiQuad bq3_H1 = bq1_H1; BiQuad bq3_H2 = bq1_H2; BiQuad bq4_H1 = bq1_H1; BiQuad bq4_H2 = bq1_H2; BiQuadChain bqc1_high; BiQuadChain bqc2_high; BiQuadChain bqc3_high; BiQuadChain bqc4_high; // Lowpass biquad filter coefficients (butter 4th order @5Hz cutoff) from MATLAB: BiQuad bq1_L1(5.32116245737504e-08, 1.06423249147501e-07, 5.32116245737504e-08, 1, -1.94396715039462, 0.944882378004138); // b01 b11 b21 a01 a11 a21 BiQuad bq1_L2(1, 2, 1, 1, -1.97586467534468, 0.976794920438162); // b02 b12 b22 a02 a12 a22 BiQuad bq2_L1 = bq1_L1; BiQuad bq2_L2 = bq1_L2; BiQuad bq3_L1 = bq1_L1; BiQuad bq3_L2 = bq1_L2; BiQuad bq4_L1 = bq1_L1; BiQuad bq4_L2 = bq1_L2; BiQuadChain bqc1_low; BiQuadChain bqc2_low; BiQuadChain bqc3_low; BiQuadChain bqc4_low; // Function to check filter stability bool checkBQChainStable() { bool n_stable = bqc1_notch.stable(); // Check stability of all BQ Chains bool hp_stable = bqc1_high.stable(); bool l_stable = bqc1_low.stable(); if (n_stable && hp_stable && l_stable) { return true; } else { return false; } } /* ------------------------------ EMG GLOBAL FUNCTIONS ------------------------------ */ void EMGOperationFunc() { emg1_norm = emg1_env * emg1_factor; // Normalize current EMG signal with calibrated factor emg2_norm = emg2_env * emg2_factor; // Idem emg3_norm = emg3_env * emg3_factor; // Idem emg4_norm = emg4_env * emg4_factor; // Idem // Set normalized EMG output signal (CAN BE MOVED TO EXTERNAL FUNCTION BECAUSE IT IS REPEATED 3 TIMES) if ( emg1_norm < emg1_th ) { // If below threshold, emg_out = 0 (ignored) emg1_out = 0.0; } else if ( emg1_norm > 1.0f ) { // If above MVC (e.g. due to filtering), emg_out = 1 (max value) emg1_out = 1.0; } else { // If in between threshold and MVC, scale EMG signal accordingly // Inputs may be in range [emg_th, 1] // Outputs are scaled to range [0, 1] emg1_out = rescale(emg1_norm, 0, 1, emg1_th, 1); } // Idem for emg2 if ( emg2_norm < emg2_th ) { emg2_out = 0.0; } else if ( emg2_norm > 1.0f ) { emg2_out = 1.0; } else { emg2_out = rescale(emg2_norm, 0, 1, emg2_th, 1); } // Idem for emg3 if ( emg3_norm < emg3_th ) { emg1_dir = 1.0; } else { emg1_dir = -1.0; } if ( emg4_norm < emg4_th ) { emg2_dir = 1.0; } else { emg2_dir = -1.0; } } /* ------------------------------ EMG SUBSTATE FUNCTIONS ------------------------------ */ // EMG Waiting state void do_emg_wait() { // Entry function if ( emg_state_changed == true ) { emg_state_changed = false; // Disable entry functions button1.fall( &button1Press ); // Change to state MVC calibration on button1 press button2.fall( &button2Press ); // Change to state rest calibration on button2 press } // Do nothing until end condition is met // State transition guard if ( button1_pressed ) { // MVC calibration button1_pressed = false; // Disable button pressed function until next button press button1.fall( NULL ); // Disable interrupt during calibration button2.fall( NULL ); // Disable interrupt during calibration emg_curr_state = emg_cal_MVC; // Set next state emg_state_changed = true; // Enable entry functions } else if ( button2_pressed ) { // Rest calibration button2_pressed = false; // Disable button pressed function until next button press button1.fall( NULL ); // Disable interrupt during calibration button2.fall( NULL ); // Disable interrupt during calibration emg_curr_state = emg_cal_rest; // Set next state emg_state_changed = true; // Enable entry functions } else if ( emg_MVC_cal_done && emg_rest_cal_done ) { // Operation mode button1.fall( NULL ); // Disable interrupt during operation button2.fall( NULL ); // Disable interrupt during operation emg_curr_state = emg_operation; // Set next state emg_state_changed = true; // Enable entry functions } } // EMG Calibration state void do_emg_cal() { // Entry functions if ( emg_state_changed == true ) { emg_state_changed = false; // Disable entry functions led_b = 0; // Turn on calibration led timerCalibration.reset(); timerCalibration.start(); // Sets up timer to stop calibration after Tcal seconds emg_sampleNow = true; // Enable signal sampling in sampleSignals() emg_calibrateNow = true; // Enable calibration vector functionality in sampleSignals() emg1_cal.reserve(Fs * Tcal); // Initialize vector lengths to prevent memory overflow emg2_cal.reserve(Fs * Tcal); // Idem emg3_cal.reserve(Fs * Tcal); // Idem emg4_cal.reserve(Fs * Tcal); // Idem } // Do stuff until end condition is met // Set HIDScope outputs scope.set(0, emg1 ); scope.set(1, emg2 ); scope.set(2, emg3 ); scope.set(3, emg4 ); //scope.set(2, emg2_env ); //scope.set(3, emg3_env ); scope.send(); // State transition guard if ( timerCalibration.read() >= Tcal ) { // After interval Tcal the calibration step is finished emg_sampleNow = false; // Disable signal sampling in sampleSignals() emg_calibrateNow = false; // Disable calibration sampling led_b = 1; // Turn off calibration led // Extract EMG scale data from calibration switch( emg_curr_state ) { case emg_cal_MVC: // In case of MVC calibration emg1_MVC = getMax(emg1_cal); // Store max value of MVC globally emg2_MVC = getMax(emg2_cal); emg3_MVC = getMax(emg3_cal); emg4_MVC = getMax(emg4_cal); emg_MVC_cal_done = true; // Set up transition to EMG operation mode break; case emg_cal_rest: // In case of rest calibration emg1_rest = getMean(emg1_cal); // Store mean of EMG in rest globally emg2_rest = getMean(emg2_cal); emg3_rest = getMean(emg3_cal); emg4_rest = getMean(emg4_cal); emg_rest_cal_done = true; // Set up transition to EMG operation mode break; } vector<double>().swap(emg1_cal); // Empty vector to prevent memory overflow vector<double>().swap(emg2_cal); vector<double>().swap(emg3_cal); vector<double>().swap(emg4_cal); emg_curr_state = emg_wait; // Set next substate emg_state_changed = true; // Enable substate entry function } } // EMG Operation state void do_emg_operation() { // Entry function if ( emg_state_changed == true ) { emg_state_changed = false; // Disable entry functions // Compute scale factors for all EMG signals double margin_percentage = 5; // Set up % margin for rest emg1_factor = 1 / emg1_MVC; // Factor to normalize MVC emg1_th = emg1_rest * emg1_factor + margin_percentage/100; // Set normalized rest threshold emg2_factor = 1 / emg2_MVC; // Factor to normalize MVC emg2_th = emg2_rest * emg2_factor + margin_percentage/100; // Set normalized rest threshold emg3_factor = 1 / emg3_MVC; // Factor to normalize MVC emg3_th = emg3_rest * emg3_factor + margin_percentage/100; // Set normalized rest threshold emg4_factor = 1 / emg4_MVC; // Factor to normalize MVC emg4_th = emg4_rest * emg4_factor + margin_percentage/100; // Set normalized rest threshold } // This state only runs its entry functions ONCE and then exits the EMG substate machine // State transition guard if ( true ) { // EMG substate machine is terminated directly after running this state once emg_curr_state = emg_wait; // Set next state emg_state_changed = true; // Enable entry function emg_cal_done = true; // Let the global substate machine know that EMG calibration is finished // Enable buttons again button1.fall( &button1Press ); button2.fall( &button2Press ); } } /* ------------------------------ MOTOR GLOBAL VARIABLES & CONSTANTS ------------------------------ */ // Initialize encoder int encoder_res = 64; QEI encoder1(D9, D8, NC, encoder_res, QEI::X4_ENCODING); //Encoder of motor 1 QEI encoder2(D12, D13, NC, encoder_res, QEI::X4_ENCODING); //Encoder of motor 2 // Initialize variables for encoder reading volatile int counts1; volatile int counts1af; int counts1offset; volatile int countsPrev1 = 0; volatile int deltaCounts1; volatile int counts2; volatile int counts2af; int counts2offset; volatile int countsPrev2 = 0; volatile int deltaCounts2; // PWM period const float PWM_period = 1/(18*10e3); // 18000 Hz // Important constants const double pi = 3.141592; // pi const double pi2 = pi * 2; // 2 pi const double deg2rad = pi / 180; //Conversion factor degree to rad const double rad2deg = 180 / pi; //Conversion factor rad to degree const double gearratio1 = 110 / 20; // Teeth of large gear : teeth of driven gear const double gearratio2 = 55 / 20; // Teeth of small gear : teeth of driven gear const double encoder_factorin = pi2 / encoder_res; // Convert encoder counts to angle in rad const float gearbox_ratio = 131.25; // Gear ratio of motor gearboxes // Kinematics variables const float l1 = 26.0; // Distance base-joint2 [cm] const float l2 = 62.0; // Distance join2-endpoint [cm] float q1 = -10.0 * deg2rad; // Angle of first joint [rad] (starts off in reference position) float q1dot; // Velocity of first joint [rad/s] float q2 = -140.0 * deg2rad; float q2dot; float Vx = 0.0; // Desired linear velocity x direction float Vy = 0.0; // Desired linear velocity y direction float xe; // Endpoint x position [cm] float ye; // Endpoint y position [cm] // Motor angles in starting position const float motor1_init = ( q1 + q2 ) * gearratio1; // Measured angle motor 1 in initial (starting) position float motor1_ref = motor1_init; // Expected motor angle float motor1_angle = motor1_init; // Actual motor angle const float motor2_init = q1 * gearratio2; // Measured angle motor 2 in initial (starting) position float motor2_ref = motor2_init; float motor2_angle = motor2_init; // Initialize variables for motor control float motor1offset; // Offset during calibration float omega1; //velocity (rad/s) bool motordir1; // Toggle of motor direction double controlsignal1; // ?? float motor1_error; // Error between encoder and reference float motor2offset; float omega2; bool motordir2; double controlsignal2; float motor2_error; // Initialize variables for PID controller float Kp = 0.27; // Proportional gain float Ki = 0.35; // Integral gain float Kd = 0.1; // Derivative gain float Ka = 1.0; float u_p1; // float u_i1; // float ux1; // float up1; // Proportional contribution float ek1; // float ei1 = 0.0; // Integral error (starts at 0) float u_p2; float u_i2; float ux2; float up2; float ek2; float ei2 = 0.0; /* ------------------------------ MOTOR FUNCTIONS ------------------------------ */ void PID_controller() { // Motor 1 static float error_integral1 = 0; static float e_prev1 = motor1_error; //Proportional part u_p1 = Kp * motor1_error; //Integral part error_integral1 = error_integral1 + ei1 * Ts; u_i1 = Ki * error_integral1; //Derivative part float error_derivative1 = (motor1_error - e_prev1) / Ts; float u_d1 = Kd * error_derivative1; e_prev1 = motor1_error; // Sum and limit up1 = u_p1 + u_i1 + u_d1; if ( up1 > 1 ) { controlsignal1 = 1; } else if ( up1 < -1 ) { controlsignal1 = -1; } else { controlsignal1 = up1; } // To prevent windup ux1 = up1 - controlsignal1; ek1 = Ka * ux1; ei1 = motor1_error - ek1; // Motor 2 static float error_integral2 = 0; static float e_prev2 = motor2_error; //Proportional part: u_p2 = Kp * motor2_error; //Integral part error_integral2 = error_integral2 + ei2 * Ts; u_i2 = Ki * error_integral2; //Derivative part float error_derivative2 = (motor2_error - e_prev2) / Ts; float u_d2 = Kd * error_derivative2; e_prev2 = motor2_error; // Sum and limit up2 = u_p2 + u_i2 + u_d2; if ( up2 > 1.0f ) { controlsignal2 = 1.0f; } else if ( up2 < -1 ) { controlsignal2 = -1.0f; } else { controlsignal2 = up2; } // To prevent windup ux2 = up2 - controlsignal2; ek2 = Ka * ux2; ei2 = motor2_error - ek2; } void RKI() { // Derived function for angular velocity of joint angles q1dot = (l2*cos(q1+q2)*Vx+l2*sin(q1+q2)*Vy)/((-l1*sin(q1)-l2*sin(q1+q2))*l2*cos(q1+q2)+l2*sin(q1+q2)*(l1*cos(q1)+l2*cos(q1+q2))); q2dot = ((-l1*cos(q1)-l2*cos(q1+q2))*Vx+(-l1*sin(q1)-l2*sin(q1+q2))*Vy)/((-l1*sin(q1)-l2*sin(q1+q2))*l2*cos(q1+q2)+l2*sin(q1+q2)*(l1*cos(q1)+l2*cos(q1+q2))); q1 = q1 + q1dot * Ts; q2 = q2 + q2dot * Ts; xe = l1 * cos(q1) + l2 * cos(q1+q2); ye = l1 * sin(q1) + l2 * sin(q1+q2); if ( q1 < -5.0f * deg2rad) { q1 = -5.0 * deg2rad; } else if ( q1 > 65.0f*deg2rad ) { q1 = 65.0f * deg2rad; } else { q1 = q1; } if ( q2 > -50.0*deg2rad ) { q2 = -50.0 * deg2rad; } else if ( q2 < -138.0*deg2rad ) { q2 = -138.0 * deg2rad; } else { q2 = q2; } motor1_ref = 5.5f * q1 + 5.5f * q2; motor2_ref = 2.75f * q1; } void motorControl() { counts1 = counts1af - counts1offset; motor1_angle = (counts1 * encoder_factorin / gearbox_ratio) + motor1_init; // Angle of motor shaft in rad + correctie voor q1 en q2 omega1 = deltaCounts1 / Ts * encoder_factorin / gearbox_ratio; // Angular velocity of motor shaft in rad/s motor1_error = motor1_ref - motor1_angle; if ( controlsignal1 < 0 ) { motordir1 = 0; } else { motordir1 = 1; } motor1Power.write(abs(controlsignal1)); motor1Direction = motordir1; counts2 = counts2af - counts2offset; motor2_angle = (counts2 * encoder_factorin / gearbox_ratio) + motor2_init; // Angle of motor shaft in rad + correctie voor q1 omega2 = deltaCounts2 / Ts * encoder_factorin / gearbox_ratio; // Angular velocity of motor shaft in rad/s motor2_error = motor2_ref-motor2_angle; if ( controlsignal2 < 0 ) { motordir2 = 0; } else { motordir2 = 1; } if (motor_encoder_cal_done == true) { motor2Power.write(abs(controlsignal2)); } motor2Direction = motordir2; } void changeservo() { butt1= extButton1.read(); if (butt1==1){ myservo.SetPosition(2000); } else { myservo.SetPosition(1000); } } void motorKillPower() { motor1Power.write(0.0f); motor2Power.write(0.0f); Vx=0.0f; Vy=0.0f; } /* ------------------------------ MOTOR SUBSTATE FUNCTIONS ------------------------------ */ void do_motor_wait() { // Entry function if ( motor_state_changed == true ) { motor_state_changed = false; } PID_controller(); motorControl(); // State transition guard if ( button2_pressed ) { button2_pressed = false; motor_curr_state = motor_encoder_set; //Beginnen met calibratie motor_state_changed = true; } } void do_motor_encoder_set() { // Entry function if ( motor_state_changed == true ) { motor_state_changed = false; // More functions } motor1Power.write(0.0f); motor2Power.write(0.0f); counts1offset = counts1af ; counts2offset = counts2af; // State transition guard if ( button2_pressed ) { button2_pressed = false; motor_encoder_cal_done = true; motor_curr_state = motor_finish; motor_state_changed = true; } } void do_motor_finish() { // Entry function if ( motor_state_changed == true ) { motor_state_changed = false; } // Do stuff until end condition is true PID_controller(); motorControl(); RKI(); // State transition guard if ( button2_pressed ) { button2_pressed = false; motor_cal_done = true; motor_curr_state = motor_wait; motor_state_changed = true; } } /* ------------------------------ OPERATION GLOBAL VARIABLES & CONSTANTS ------------------------------ */ /* ------------------------------ OPERATION GLOBAL FUNCTIONS ------------------------------ */ void toggleServo() { if ( operation_showcard == true ) { myservo.SetPosition(2000); operation_showcard = !operation_showcard; } else { myservo.SetPosition(1000); operation_showcard = !operation_showcard; } } /* ------------------------------ OPERATION SUBSTATE FUNCTIONS ------------------------------ */ void do_operation_wait() { // Entry function if ( operation_state_changed == true ) { operation_state_changed = false; emg_sampleNow = false; // Disable signal sampling in sampleSignals() emg_calibrateNow = false; // Disable calibration functionality in sampleSignals() } // Do stuff until end condition is met EMGOperationFunc(); Vx = emg1_out * 15.0f * emg1_dir; Vy = emg2_out * 15.0f * emg2_dir; PID_controller(); motorControl(); RKI(); motorKillPower(); // Disables motor outputs if ( switch2_pressed == true) { switch2_pressed = false; toggleServo(); } // State transition guard if ( button1_pressed == true ) { button1_pressed = false; operation_curr_state = operation_movement; operation_state_changed = true; } else if ( button2_pressed == true ) { button2_pressed = false; //operation_curr_state = operation_finish; // To move to finished operation mode (not used yet) operation_curr_state = operation_wait; // TEMPORARY operation_state_changed = true; global_curr_state = global_wait; // TEMPORARY move directly to global wait state global_state_changed = true; // TEMPORARY move directly to global wait state } } void do_operation_movement() { // Entry function if ( operation_state_changed == true ) { operation_state_changed = false; emg_sampleNow = true; // Enable signal sampling in sampleSignals() emg_calibrateNow = false; // Disable calibration functionality in sampleSignals() } // Do stuff until end condition is met EMGOperationFunc(); Vx = emg1_out * 15.0f * emg1_dir; Vy = emg2_out * 15.0f * emg2_dir; PID_controller(); motorControl(); RKI(); if ( switch2_pressed == true) { switch2_pressed = false; toggleServo(); } // State transition guard if ( button1_pressed == true ) { button1_pressed = false; operation_curr_state = operation_wait; operation_state_changed = true; } else if ( button2_pressed == true ) { button2_pressed = false; //operation_curr_state = operation_finish; // To move to finished operation mode (not used yet) operation_curr_state = operation_wait; // TEMPORARY operation_state_changed = true; global_curr_state = global_wait; // TEMPORARY move directly to global wait state global_state_changed = true; // TEMPORARY move directly to global wait state } } void do_operation_finish() // NOT USED YET { // Entry function if ( operation_state_changed == true ) { operation_state_changed = false; emg_sampleNow = false; // Enable signal sampling in sampleSignals() emg_calibrateNow = false; // Disable calibration functionality in sampleSignals() } // Do stuff until end condition is met EMGOperationFunc(); Vx = emg1_out * 15.0f * emg1_dir; Vy = emg2_out * 15.0f * emg2_dir; PID_controller(); motorControl(); RKI(); // Function to move to starting position // State transition guard if ( button2_pressed == true ) { button2_pressed = false; operation_curr_state = operation_wait; operation_state_changed = true; global_curr_state = global_wait; global_state_changed = true; } } /* ------------------------------ EMG SUBSTATE MACHINE ------------------------------ */ void emg_state_machine() { switch(emg_curr_state) { case emg_wait: do_emg_wait(); break; case emg_cal_MVC: do_emg_cal(); break; case emg_cal_rest: do_emg_cal(); break; case emg_operation: do_emg_operation(); break; } } /* ------------------------------ MOTOR SUBSTATE MACHINE ------------------------------ */ void motor_state_machine() { switch(motor_curr_state) { case motor_wait: do_motor_wait(); break; case motor_encoder_set: do_motor_encoder_set(); break; case motor_finish: do_motor_finish(); break; } } /* ------------------------------ OPERATION SUBSTATE MACHINE ------------------------------ */ void operation_state_machine() { switch(operation_curr_state) { case operation_wait: do_operation_wait(); break; case operation_movement: do_operation_movement(); break; case operation_finish: do_operation_finish(); break; } } /* ------------------------------ DEMO SUBSTATE FUNCTIONS ------------------------------ */ void do_demo_wait() { // Entry function if ( demo_state_changed == true ) { demo_state_changed = false; } // Do nothing until end condition is met // State transition guard if ( button1_pressed == true ) { // demo_XY button1_pressed = false; demo_curr_state = demo_XY; demo_state_changed = true; // More functions } else if (button2_pressed == true) { // Return to global wait button2_pressed = false; demo_curr_state = demo_wait; demo_state_changed = true; motor_cal_done = false; // Disables motor calibration again (robot is probably not in reference position) global_curr_state = global_wait; global_state_changed = true; } } void do_demo_motor_cal() { // Entry function if ( demo_state_changed == true ) { demo_state_changed = false; } // Do stuff until end condition is met motor_state_machine(); // State transition guard if ( motor_cal_done == true ) { // demo_wait demo_curr_state = demo_wait; demo_state_changed = true; } } void do_demo_XY() { // Entry function if ( demo_state_changed == true ) { demo_state_changed = false; } // Do stuff until end condition is met static float t = 0; Vy = 10.0f * sin(1.0f*t); Vx = 0.0f; t += Ts; PID_controller(); motorControl(); RKI(); // State transition guard if ( button1_pressed == true ) { // demo_wait button1_pressed = false; demo_curr_state = demo_wait; demo_state_changed = true; } } /* ------------------------------ DEMO SUBSTATE MACHINE ------------------------------ */ void demo_state_machine() { switch(demo_curr_state) { case demo_wait: do_demo_wait(); break; case demo_motor_cal: do_demo_motor_cal(); break; case demo_XY: do_demo_XY(); break; } } /* ------------------------------ GLOBAL STATE FUNCTIONS ------------------------------ */ /* ALL STATES HAVE THE FOLLOWING FORM: void do_state_function() { // Entry function if ( global_state_changed == true ) { global_state_changed = false; // More functions } // Do stuff until end condition is met doStuff(); // State transition guard if ( endCondition == true ) { global_curr_state = next_state; global_state_changed = true; // More functions } } */ // FAILURE MODE void do_global_failure() { // Entry function if ( global_state_changed == true ) { global_state_changed = false; failure_mode = true; // Set failure mode } // Do stuff until end condition is met motorKillPower(); // State transition guard if ( false ) { // Never move to other state global_curr_state = global_wait; global_state_changed = true; } } // DEMO MODE void do_global_demo() { // Entry function if ( global_state_changed == true ) { global_state_changed = false; // More functions } // Do stuff until end condition is met demo_state_machine(); scope.set(0, emg1 ); scope.set(1, Vx ); scope.set(2, emg2 ); scope.set(3, Vy ); // State transition guard if ( switch2_pressed == true ) { switch2_pressed = false; global_curr_state = global_wait; global_state_changed = true; } } // WAIT MODE void do_global_wait() { // Entry function if ( global_state_changed == true ) { global_state_changed = false; } // Do nothing until end condition is met // State transition guard if ( switch2_pressed == true ) { // DEMO MODE switch2_pressed = false; global_curr_state = global_demo; global_state_changed = true; } else if ( button1_pressed == true ) { // EMG CALIBRATION button1_pressed = false; global_curr_state = global_emg_cal; global_state_changed = true; } else if ( button2_pressed == true ) { // MOTOR CALIBRATION button2_pressed = false; global_curr_state = global_motor_cal; global_state_changed = true; } else if ( emg_cal_done && motor_cal_done ) { // OPERATION MODE global_curr_state = global_operation; global_state_changed = true; } } // EMG CALIBRATION MODE void do_global_emg_cal() { // Entry function if ( global_state_changed == true ) { global_state_changed = false; } // Run EMG state machine until emg_cal_done flag is true emg_state_machine(); // State transition guard if ( emg_cal_done == true ) { // WAIT MODE global_curr_state = global_wait; global_state_changed = true; } } // MOTOR CALIBRATION MODE void do_global_motor_cal() { // Entry function if ( global_state_changed == true ) { global_state_changed = false; } // Do stuff until end condition is met motor_state_machine(); // State transition guard if ( motor_cal_done == true ) { // WAIT MODE global_curr_state = global_wait; global_state_changed = true; } } // OPERATION MODE void do_global_operation() { // Entry function if ( global_state_changed == true ) { global_state_changed = false; emg_sampleNow = true; // Enable signal sampling in sampleSignals() emg_calibrateNow = false; // Disable calibration functionality in sampleSignals() } // Do stuff until end condition is met operation_state_machine(); // Set HIDScope outputs scope.set(0, emg1 ); scope.set(1, Vx ); scope.set(2, emg2 ); scope.set(3, Vy ); scope.send(); led_g = !led_g; // State transition guard if ( false ) { // Always stay in operation mode (can be changed) global_curr_state = global_wait; global_state_changed = true; } } /* ------------------------------ GLOBAL STATE MACHINE ------------------------------ */ void global_state_machine() { switch(global_curr_state) { case global_failure: do_global_failure(); break; case global_wait: do_global_wait(); break; case global_emg_cal: do_global_emg_cal(); break; case global_motor_cal: do_global_motor_cal(); break; case global_operation: do_global_operation(); break; case global_demo: do_global_demo(); break; } } /* ------------------------------ READ SAMPLES ------------------------------ */ void sampleSignals() { if (emg_sampleNow == true) { // This ticker only samples if the sample flag is true, to prevent unnecessary computations // Read EMG inputs emg1 = emg1_in.read(); emg2 = emg2_in.read(); emg3 = emg3_in.read(); emg4 = emg4_in.read(); double emg1_n = bqc1_notch.step( emg1 ); // Filter notch double emg1_hp = bqc1_high.step( emg1_n ); // Filter highpass double emg1_rectify = fabs( emg1_hp ); // Rectify emg1_env = bqc1_low.step( emg1_rectify ); // Filter lowpass (completes envelope) double emg2_n = bqc2_notch.step( emg2 ); // Filter notch double emg2_hp = bqc2_high.step( emg2_n ); // Filter highpass double emg2_rectify = fabs( emg2_hp ); // Rectify emg2_env = bqc2_low.step( emg2_rectify ); // Filter lowpass (completes envelope) double emg3_n = bqc3_notch.step( emg3 ); // Filter notch double emg3_hp = bqc3_high.step( emg3_n ); // Filter highpass double emg3_rectify = fabs( emg3_hp ); // Rectify emg3_env = bqc3_low.step( emg3_rectify ); // Filter lowpass (completes envelope) double emg4_n = bqc4_notch.step( emg4 ); // Filter notch double emg4_hp = bqc4_high.step( emg4_n ); // Filter highpass double emg4_rectify = fabs( emg4_hp ); // Rectify emg4_env = bqc4_low.step( emg4_rectify ); // Filter lowpass (completes envelope) if (emg_calibrateNow == true) { // Only add values to EMG vectors if calibration flag is true emg1_cal.push_back(emg1_env); // Add values to calibration vector emg2_cal.push_back(emg2_env); // Add values to calibration vector emg3_cal.push_back(emg3_env); // Add values to calibration vector emg4_cal.push_back(emg4_env); // Add values to calibration vector } } counts1af = encoder1.getPulses(); deltaCounts1 = counts1af - countsPrev1; countsPrev1 = counts1af; counts2af = encoder2.getPulses(); deltaCounts2 = counts2af - countsPrev2; countsPrev2 = counts2af; } /* ------------------------------ GLOBAL PROGRAM LOOP ------------------------------ */ void tickGlobalFunc() { sampleSignals(); global_state_machine(); changeservo(); // controller(); // outputToMotors(); } /* ------------------------------ MAIN FUNCTION ------------------------------ */ int main() { pc.baud(115200); // MODSERIAL rate pc.printf("Starting\r\n"); global_curr_state = global_wait; // Start off in EMG Wait state tickGlobal.attach( &tickGlobalFunc, Ts ); // Start global ticker // ---------- Attach filters ---------- bqc1_notch.add( &bq1_notch ); bqc1_high.add( &bq1_H1 ).add( &bq1_H2 ); bqc1_low.add( &bq1_L1 ).add( &bq1_L2 ); bqc2_notch.add( &bq2_notch ); bqc2_high.add( &bq2_H1 ).add( &bq2_H2 ); bqc2_low.add( &bq2_L1 ).add( &bq2_L2 ); bqc3_notch.add( &bq3_notch ); bqc3_high.add( &bq3_H1 ).add( &bq3_H2 ); bqc3_low.add( &bq3_L1 ).add( &bq3_L2 ); bqc4_notch.add( &bq4_notch ); bqc4_high.add( &bq4_H1 ).add( &bq4_H2 ); bqc4_low.add( &bq4_L1 ).add( &bq4_L2 ); // ---------- Attach buttons ---------- button1.fall( &button1Press ); button2.fall( &button2Press ); switch2.fall( &switch2Press ); switch3.fall( &switch3Press ); extButton1.mode(PullUp); // ---------- Attach PWM ---------- motor1Power.period(PWM_period); motor2Power.period(PWM_period); // ---------- Turn OFF LEDs ---------- led_b = 1; led_g = 1; led_r = 1; while(true) { pc.printf("Global state: %i EMG state: %i Motor state: %i Operation state: %i Demo state: %i\r\n", global_curr_state, emg_curr_state, motor_curr_state, operation_curr_state, demo_curr_state); //pc.printf("EMG1 direction: %f EMG2 direction: %f \r\n", emg1_dir, emg2_dir); pc.printf("q1: %f q2: %f \r\n",q1*rad2deg,q2*rad2deg); pc.printf("Motor1ref: %f Motor1angle: %f\r\n",motor1_ref,motor1_angle); pc.printf("Motor2ref: %f Motor2angle: %f\r\n",motor2_ref,motor2_angle); pc.printf("Counts2: %i Counts2af: %i Counts2offset: %i \r\n", counts2, counts2af, counts2offset); //pc.printf("Xe: %f Ye: %f\r\n",xe,ye); wait(0.5f); } }