De hele robot in 1 keer bam
Dependencies: mbed QEI Servo HIDScope biquadFilter MODSERIAL FastPWM
main.cpp
- Committer:
- BasB
- Date:
- 2019-11-05
- Revision:
- 68:2879967ebb25
- Parent:
- 63:d17f45d88c7a
- Child:
- 69:bfefdfb04c29
File content as of revision 68:2879967ebb25:
/* ------------------------------ 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 // Analog Potmeter inputs AnalogIn potmeter1 (A4); AnalogIn potmeter2 (A5); // Motor 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); /* ------------------------------ INITIALIZE TICKERS, TIMERS & TIMEOUTS ------------------------------ */ Ticker tickGlobal; // Set global ticker Ticker tickLED; // LED ticker Timer timerStateChange; // Set timer for various state changes /* ------------------------------ 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_encoder_set, motor_finish }; // Define motor substates Motor_States motor_curr_state = motor_encoder_set; // 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 bool exit_operation = false; // Demo Substate variables enum Demo_States { demo_wait, demo_motor_cal, demo_positioning, demo_XY }; // Define demo substates Demo_States demo_curr_state; // Initialize demo substate variable bool demo_state_changed = true; // Enable entry functions bool exit_demo = false; // Button press interrupts (to prevent bounce) bool button1_pressed = false; bool button2_pressed = false; bool switch2_pressed = false; bool servo_button1; // LED states enum LED_Colors { off, red, green, blue, purple, yellow, cyan, white }; // Define possible LED colors LED_Colors curr_led_color; // Initialize LED color variable bool led_color_changed = true; // Enable LED entry functions // Global constants const double Fs = 500.0; //Sampling frequency const double Ts = 1/Fs; /* ------------------------------ LED COLOR FUNCTIONS ------------------------------ */ // Only called once when color is changed void set_led_color(char color) { switch(color) { case 'o': curr_led_color = off; break; case 'r': curr_led_color = red; break; case 'b': curr_led_color = blue; break; case 'g': curr_led_color = green; break; case 'y': curr_led_color = yellow; break; case 'p': curr_led_color = purple; break; case 'c': curr_led_color = cyan; break; case 'w': curr_led_color = white; break; } led_color_changed = true; } // Run constantly void disp_led_color() { if (led_color_changed == true) { led_color_changed = false; led_g = 1; led_b = 1; led_r = 1; } switch(curr_led_color) { case off: break; case red: led_r = !led_r; break; case blue: led_b = !led_b; break; case green: led_g = !led_g; break; case yellow: led_r = !led_r; led_g = !led_g; break; case purple: led_r = !led_r; led_b = !led_b; break; case cyan: led_b = !led_b; led_g = !led_g; break; case white: led_r = !led_r; led_g = !led_g; led_b = !led_b; break; } } /* ------------------------------ HELPER FUNCTIONS ------------------------------ */ // 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 set_led_color('b'); // Turn on calibration led (BLUE) timerStateChange.reset(); timerStateChange.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 ( timerStateChange.read() >= Tcal ) { // After interval Tcal the calibration step is finished emg_sampleNow = false; // Disable signal sampling in sampleSignals() emg_calibrateNow = false; // Disable calibration sampling set_led_color('p'); // Change calibration LED (BLUE) to EMG wait mode led (PURPLE) // 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 ); } } /* ------------------------------ 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 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; //Counts after compensation with offset volatile int counts1af; //Counts measured by encoder int counts1offset; //Offset due to calibration volatile int countsPrev1 = 0; volatile int deltaCounts1; volatile int counts2; // Counts after compensation with offset volatile int counts2af; //Counts measured by encoder int counts2offset; //Offset due to calibration volatile int countsPrev2 = 0; volatile int deltaCounts2; // PWM period const float PWM_period = 1/(18*10e3); // 18000 Hz // Important constants const float pi = 3.141592; // pi const float pi2 = pi * 2.0f; // 2 pi const float deg2rad = pi / 180.0f; //Conversion factor degree to rad const float rad2deg = 180.0f / pi; //Conversion factor rad to degree const float gearratio1 = 110.0f / 20.0f; // Teeth of large gear : teeth of driven gear const float gearratio2 = 55.0f / 20.0f; // Teeth of small gear : teeth of driven gear const float 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.0f * deg2rad; // Angle of first joint [rad] (in calibration position) float q1dot; // Velocity of first joint [rad/s] float q2 = -140.0f * deg2rad; // Angle of second joint [rad] (in calibration position float q2dot; // Velocity of second joint [rad/s] float Vx = 0.0; // Desired linear velocity x direction [cm/s] float Vy = 0.0; // Desired linear velocity y direction [cm/s] 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 (starting from initial position) 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; // Motor 2 reference position (starting from initial position) float motor2_angle = motor2_init; // Actual motor angle // Initialize variables for motor control float motor1offset; // Offset during calibration float omega1; //angular velocity of motor [rad/s] bool motordir1; // Toggle of motor direction double controlsignal1; // Result of the PID controller float motor1_error; // Error between desired and actual angle of the motor float motor2offset; // Offset during calibration float omega2; //Angular velocity of motor [rad/s] bool motordir2; // Toggle of motor direction double controlsignal2; // Result of the PID controller float motor2_error; // Error between desired and actual angle of the motor // 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; //Windup gain float u_p1; // Proportional contribution float u_i1; // Integral contribution float u_d1; // Derivative contribution float ux1; // Windup error (before multiplication with Ka) float up1; // Summed contributions float ek1; // Windup error float ei1 = 0.0; // Integral error (starts at 0) float u_p2; // Proportional contribution float u_i2; // Integral contribution float u_d2; // Derivative contribution float ux2; // Windup error (before multiplication with Ka) float up2; // Summed contributions float ek2; // Windup error float ei2 = 0.0; // Integral error (starts at 0) /* ------------------------------ MOTOR FUNCTIONS ------------------------------ */ void PID_controller() { // Motor 1 static float error_integral1 = 0.0; static float e_prev1 = motor1_error; // Saving the previous error, needed for derivative computation //Proportional part u_p1 = Kp * motor1_error; //Integral part if ( motor_curr_state == motor_finish || operation_curr_state == operation_movement || demo_curr_state == demo_XY || demo_curr_state == demo_positioning ) { // Only active during operational states to prevent windup 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; // Sum the contributions of P, I and D if ( up1 > 1.0f ) { // Saturated limit of motor, contintue with value between -1 and 1 controlsignal1 = 1.0f; } else if ( up1 < -1.0f ) { controlsignal1 = -1.0f; } else { controlsignal1 = up1; } // To prevent windup ux1 = up1 - controlsignal1; // Computation of the overflow ek1 = Ka * ux1; ei1 = motor1_error - ek1; // Integral error with windup subtracted // Motor 2 static float error_integral2 = 0.0; static float e_prev2 = motor2_error; // Saving the previous error, needed for derivative computation //Proportional part: u_p2 = Kp * motor2_error; //Integral part if ( motor_curr_state == motor_finish || operation_curr_state == operation_movement || demo_curr_state == demo_XY || demo_curr_state == demo_positioning ) { // Only active during operational states to prevent windup 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; // Sum the contributions of P, I and D if ( up2 > 1.0f ) { // Saturated limit of motor, contintue with value between -1 and 1 controlsignal2 = 1.0f; } else if ( up2 < -1.0f ) { controlsignal2 = -1.0f; } else { controlsignal2 = up2; } // To prevent windup ux2 = up2 - controlsignal2; // Computation of the overflow ek2 = Ka * ux2; ei2 = motor2_error - ek2; // Integral error with windup subtracted } 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))); // Computation of the desired angular velocities with given linear velocities Vx and Vy 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))); // Computation of the desired angular velocities with given linear velocities Vx and Vy q1 = q1 + q1dot * Ts; // Calculating desired joint angle by integrating the desired angular velocity q2 = q2 + q2dot * Ts; // Calculating desired joint angle by integrating the desired angular velocity xe = l1 * cos(q1) + l2 * cos(q1+q2); // Calculation of the current endpoint position ye = l1 * sin(q1) + l2 * sin(q1+q2); // Calculation of the current endpoint position if ( q1 < -5.0f * deg2rad) { // Setting limits to the joint angles q1 = -5.0f * deg2rad; } else if ( q1 > 65.0f * deg2rad ) { // Setting limits to the joint angles q1 = 65.0f * deg2rad; } else { q1 = q1; } if ( q2 > -50.0f * deg2rad ) { // Setting limits to the joint angles q2 = -50.0f * deg2rad; } else if ( q2 < -138.0f * deg2rad ) { // Setting limits to the joint angles q2 = -138.0f * deg2rad; } else { q2 = q2; } motor1_ref = 5.5f * q1 + 5.5f * q2; // Calculating the desired motor angle to attain the correct joint angles motor2_ref = 2.75f * q1; // Calculating the desired motor angle to attain the correct joint angles } void motorControl() { counts1 = counts1af - counts1offset; // Counts measured by encoder compensated with the offset due to calibration motor1_angle = (counts1 * encoder_factorin / gearbox_ratio) + motor1_init; // Angle of motor shaft [rad] + correction of initial value omega1 = deltaCounts1 / Ts * encoder_factorin / gearbox_ratio; // Angular velocity of motor shaft [rad/s] motor1_error = motor1_ref - motor1_angle; // Difference between desired and measured angle of motor if ( controlsignal1 < 0.0f ) { // Determine the direction motordir1 = 0; } else { motordir1 = 1; } motor1Power.write(abs(controlsignal1)); // Assigning the desired power to the motor motor1Direction = motordir1; // Assigning the desired direction counts2 = counts2af - counts2offset; // Counts measured by encoder compensated with the offset due to calibration motor2_angle = (counts2 * encoder_factorin / gearbox_ratio) + motor2_init; // Angle of motor shaft [rad] + correction of initial value omega2 = deltaCounts2 / Ts * encoder_factorin / gearbox_ratio; // Angular velocity of motor shaft [rad/s] motor2_error = motor2_ref-motor2_angle; // Difference between desired and measured angle of motor if ( controlsignal2 < 0.0f ) { // Determine the direction motordir2 = 0; } else { motordir2 = 1; } if (motor_encoder_cal_done == true) { motor2Power.write(abs(controlsignal2)); // Assinging the desired power to the motor } motor2Direction = motordir2; // Assigning the desired direction to the motor } void motorKillPower() { motor1Power.write(0.0f); // Setting motor power to 0 to stop motion motor2Power.write(0.0f); // Setting motor power to 0 to stop motion Vx=0.0f; // Setting desired linear motion to 0 to prevent RKI from adjusting the motorpower Vy=0.0f; // Setting desired linear motion to 0 to prevent RKI from adjusting the motorpower } /* ------------------------------ MOTOR SUBSTATE FUNCTIONS ------------------------------ */ void do_motor_encoder_set() { // Entry function if ( motor_state_changed == true ) { motor_state_changed = false; // More functions } motor1Power.write(0.0f); // Giving the motor no power to be able to adjust the robot configuration motor2Power.write(0.0f); counts1offset = counts1af ; // Storing the offset of the encoder counts2offset = counts2af; // Storing the offset of the encoder // 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; timerStateChange.reset(); timerStateChange.start(); } // Do stuff until end condition is true PID_controller(); motorControl(); //These three functions cause the robot to move within the link limits RKI(); // State transition guard if ( timerStateChange.read() >= 3.0f ) { // After 3 seconds move to next state button2_pressed = false; motor_cal_done = true; motor_curr_state = motor_encoder_set; motor_state_changed = true; } } /* ------------------------------ MOTOR SUBSTATE MACHINE ------------------------------ */ void motor_state_machine() { switch(motor_curr_state) { case motor_encoder_set: do_motor_encoder_set(); break; case motor_finish: do_motor_finish(); break; } } /* ------------------------------ 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 * (10.0 + 10.0 * potmeter1.read() ) * emg1_dir; Vy = emg2_out * (10.0 + 10.0 * potmeter2.read() ) * emg2_dir; PID_controller(); motorControl(); RKI(); motorKillPower(); // Disables motor outputs // 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 * (10.0 + 10.0 * potmeter1.read() ) * emg1_dir; Vy = emg2_out * (10.0 + 10.0 * potmeter2.read() ) * emg2_dir; PID_controller(); motorControl(); RKI(); // 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_wait; operation_state_changed = true; exit_operation = true; } } /* ------------------------------ 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; } } /* ------------------------------ 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_positioning; demo_state_changed = true; // More functions } else if ( switch2_pressed == true ) { // Return to global wait switch2_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) exit_demo = true; } } void do_demo_motor_cal() { // Entry function if ( demo_state_changed == true ) { demo_state_changed = false; set_led_color('c'); // Set LED to motor calibration (CYAN) } // 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; set_led_color('y'); // Set LED to demo mode (YELLOW) } } void do_demo_positioning() { // Entry function if ( demo_state_changed == true ) { demo_state_changed = false; timerStateChange.reset(); timerStateChange.start(); } Vx = 5.0; // Move in the positive x direction Vy = 5.0; // Move in the positive y direction PID_controller(); motorControl(); RKI(); scope.set(0, motor2_ref * rad2deg ); scope.set(1, motor2_angle * rad2deg ); scope.send(); // State transition guard if ( timerStateChange.read() >= 3.0f ) { // demo_wait button1_pressed = false; demo_curr_state = demo_XY; 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.0; if ( t >= 0.0f && t < 3.0f ) { // With this code the endpoint will make a square every 12 seconds Vx = 5.0; Vy = 0.0; } else if ( t >= 3.0f && t < 6.0f ) { Vx = 0.0; Vy = 5.0; } else if ( t >= 6.0f && t < 9.0f ) { Vx = -5.0; Vy = 0.0; } if ( t >= 9.0f && t < 12.0f ) { Vx = 0.0; Vy = -5.0; } else if ( t >= 12.0f) { t = 0.0; } t += Ts; PID_controller(); motorControl(); RKI(); scope.set(0, motor2_ref * rad2deg ); scope.set(1, motor2_angle * rad2deg ); //scope.set(2, motor2_ref ); //scope.set(3, motor2_angle ); scope.send(); // State transition guard if ( button1_pressed == true ) { // demo_wait t = 0.0; 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_positioning: do_demo_positioning(); 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; set_led_color('r'); // Set failure mode LED (RED) 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; set_led_color('o'); // Disable failure mode LED } } // DEMO MODE void do_global_demo() { // Entry function if ( global_state_changed == true ) { global_state_changed = false; set_led_color('y'); // Set demo mode LED (YELLOW) emg_cal_done = false; // Disables EMG calibration to prevent going into operation mode after exiting demo state if ( motor_cal_done == true ) { demo_curr_state = demo_wait; } else if (motor_cal_done == false ) { demo_curr_state = demo_motor_cal; } demo_state_changed = true; } // Do stuff until end condition is met demo_state_machine(); // State transition guard if ( exit_demo == true ) { exit_demo = false; global_curr_state = global_wait; global_state_changed = true; set_led_color('o'); // Disable demo mode LED motor1_ref = motor1_init; motor1_angle = motor1_init; motor2_ref = motor2_init; motor2_angle = motor2_init; } } // WAIT MODE void do_global_wait() { // Entry function if ( global_state_changed == true ) { global_state_changed = false; set_led_color('w'); // Set wait mode LED (WHITE) } // 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; set_led_color('o'); // Disable wait mode LED } else if ( button1_pressed == true ) { // EMG CALIBRATION button1_pressed = false; global_curr_state = global_emg_cal; global_state_changed = true; set_led_color('o'); // Disable wait mode LED } else if ( button2_pressed == true ) { // MOTOR CALIBRATION button2_pressed = false; global_curr_state = global_motor_cal; global_state_changed = true; set_led_color('o'); // Disable wait mode LED } else if ( emg_cal_done && motor_cal_done ) { // OPERATION MODE global_curr_state = global_operation; global_state_changed = true; set_led_color('o'); // Disable wait mode LED } } // EMG CALIBRATION MODE void do_global_emg_cal() { // Entry function if ( global_state_changed == true ) { global_state_changed = false; set_led_color('p'); // Set EMG calibration LED (PURPLE) } // 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; set_led_color('o'); // Disable EMG calibration LED } } // MOTOR CALIBRATION MODE void do_global_motor_cal() { // Entry function if ( global_state_changed == true ) { global_state_changed = false; set_led_color('c'); // Set motor calibration LED (CYAN) } // 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; set_led_color('o'); // Disable motor calibration LED } } // 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() set_led_color('g'); // Set operation led (GREEN) } // 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(); // State transition guard if ( exit_operation == true ) { exit_operation = false; global_curr_state = global_wait; global_state_changed = true; set_led_color('o'); // Disable operation led } } /* ------------------------------ 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; } } /* ------------------------------ OTHER MAIN LOOP FUNCTIONS ------------------------------ */ 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; } void changeservo() { servo_button1 = extButton1.read(); if (servo_button1 == 1) { myservo.SetPosition(2000); } else { myservo.SetPosition(1000); } } /* ------------------------------ GLOBAL PROGRAM LOOP ------------------------------ */ void tickGlobalFunc() { sampleSignals(); global_state_machine(); changeservo(); // Servo angle can be adjusted during every state } /* ------------------------------ MAIN FUNCTION ------------------------------ */ int main() { pc.baud(115200); // MODSERIAL rate pc.printf("Starting\r\n"); global_curr_state = global_wait; // Start off in global wait state tickGlobal.attach( &tickGlobalFunc, Ts ); // Start global ticker tickLED.attach ( &disp_led_color, 0.25f ); // Start LED ticker // ---------- Enable Servo ---------- myservo.Enable(1000, 20000); // ---------- 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 ); // To make sure the servo works // ---------- Attach PWM ---------- motor1Power.period(PWM_period); motor2Power.period(PWM_period); // ---------- Turn OFF LEDs ---------- set_led_color('o'); 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("Potmeter 1: %f Potmeter 2: %f\r\n", potmeter1.read(), potmeter2.read()); //pc.printf("Xe: %f Ye: %f\r\n",xe,ye); wait(0.5f); } }