De hele robot in 1 keer bam

Dependencies:   mbed QEI Servo HIDScope biquadFilter MODSERIAL FastPWM

main.cpp

Committer:
Jellehierck
Date:
2019-10-30
Revision:
41:8e8141f355af
Parent:
40:c6dffb676350
Child:
42:2937ad8f1032

File content as of revision 41:8e8141f355af:

/*
------------------------------ 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
#include "QEI.h"            // Encoder

/*
------------------------------ 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);

// 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

// Encoder inputs
DigitalIn encA1(D9);
DigitalIn encB1(D8);
DigitalIn encA2(D13);
DigitalIn encB2(D12);

// Motor outputs
DigitalOut motor2Direction(D4);
FastPWM motor2Power(D5);
DigitalOut motor1Direction(D7);
FastPWM motor1Power(D6);

/*
------------------------------ 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;

bool emg_cal_done = false;
bool motor_cal_done = false;

// 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;

bool emg_sampleNow = false;
bool emg_calibrateNow = false;
bool emg_MVC_cal_done = false;
bool emg_rest_cal_done = false;

// Motor Substate variables
enum Motor_States {motor_wait, motor_encoderset, motor_finish, motor_movement, failuremode};
Motor_States motor_curr_state = motor_wait;
bool motor_state_changed = true;

bool motor_calibration_done = false;

// 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;
}

/*
------------------------------ MOTOR CONTROL ------------------------------
*/
// Initialize encoder
QEI encoder1(D9,D8,NC,64,QEI::X4_ENCODING);     //Encoding motor 1
QEI encoder2(D13,D12,NC,64,QEI::X4_ENCODING);   //Encoding motor 2

volatile int counts1; // Encoder counts
volatile int counts2;
volatile int counts1af;
volatile int counts2af;
int counts1offset;
int counts2offset;
volatile int countsPrev1 = 0;
volatile int countsPrev2 = 0;
volatile int deltaCounts1;
volatile int deltaCounts2;

// PWM period
const float PWM_period = 1/(18*10e3);

// Degree to radian convertor
const float deg2rad = 0.0174532;                        //Conversion factor degree to rad
const float rad2deg = 57.29578;                         //Conversion factor rad to degree

// Motor angles in starting position
float motor1angle=(-140.0-10.0)*deg2rad*5.5;    //Measured angle motor 1
float motor2angle=(-10.0)*deg2rad*2.75;         //Measured angle motor 2

const float factorin = 6.23185/64; // Convert encoder counts to angle in rad
const float gearratio = 131.25; // Gear ratio of gearbox

// GLobal variales
float motor1offset;                             //Offset bij calibratie
float motor2offset;
float omega1;                                   //velocity rad/s motor 1
float omega2;                                   //Velocity rad/s motor2
bool motordir1;
bool motordir2;
float motor1ref=(-140.0-10.0)*deg2rad*5.5;
float motor2ref=(-10.0)*deg2rad*2.75;
double controlsignal1;
double controlsignal2;
double pi2= 6.283185;
float motor1error;                              //motor 1 error
float motor2error;
float Kp=0.27;
float Ki=0.35;
float Kd=0.1;
float u_p1;
float u_p2;
float u_i1;
float u_i2;

//Windup control
float ux1;
float ux2;
float up1;                                      //Proportional contribution motor 1
float up2;                                      //Proportional contribution motor 2
float ek1;
float ek2;
float ei1= 0.0;                                 //Error integral motor 1
float ei2=0.0;                                  //Error integral motor 2
float Ka= 1.0;                                  //Integral windup gain

//RKI
float Vx=0.0;                                   //Desired linear velocity x direction
float Vy=0.0;                                   //Desired linear velocity y direction
float q1=-10.0f*deg2rad;                          //Angle of first joint [rad]
float q2=-140.0f*deg2rad;                       //Angle of second joint [rad]
float q1dot;                                    //Velocity of first joint [rad/s]
float q2dot;                                    //Velocity of second joint [rad/s]
float l1=26.0;                                  //Distance base-link [cm]
float l2=62.0;                                  //Distance link-endpoint [cm]
float xe;                                       //Endpoint x position [cm]
float ye;                                       //Endpoint y position [cm]

/*
------------------------------ MOTOR FUNCTIONS ------------------------------
*/
void PID_controller()
{

    static float error_integral1=0;
    static float e_prev1=motor1error;

    //Proportional part:
    u_p1=Kp*motor1error;

    //Integral part
    error_integral1=error_integral1+ei1*Ts;
    u_i1=Ki*error_integral1;

    //Derivative part
    float error_derivative1=(motor1error-e_prev1)/Ts;
    float u_d1=Kd*error_derivative1;
    e_prev1=motor1error;

    // 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= motor1error-ek1;

// Motor 2

    static float error_integral2=0;
    static float e_prev2=motor2error;

    //Proportional part:
    u_p2=Kp*motor2error;

    //Integral part
    error_integral2=error_integral2+ei2*Ts;
    u_i2=Ki*error_integral2;

    //Derivative part
    float error_derivative2=(motor2error-e_prev2)/Ts;
    float u_d2=Kd*error_derivative2;
    e_prev2=motor2error;

    // 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= motor2error-ek2;
}

void RKI()
{
    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) {
        q1=-5.0;
    } 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;
    }

    motor1ref=5.5f*q1+5.5f*q2;
    motor2ref=2.75f*q1;
}

void motorControl()
{
    counts1= counts1af-counts1offset;
    motor1angle = (counts1 * factorin / gearratio)-((140.0*5.5*deg2rad)+(10.0*5.5*deg2rad)); // Angle of motor shaft in rad + correctie voor q1 en q2
    omega1 = deltaCounts1 / Ts * factorin / gearratio; // Angular velocity of motor shaft in rad/s
    motor1error=motor1ref-motor1angle;
    if (controlsignal1<0) {
        motordir1= 0;
    } else {
        motordir1= 1;
    }

    motor1Power.write(abs(controlsignal1));
    motor1Direction= motordir1;

    counts2= counts2af - counts2offset;
    motor2angle = (counts2 * factorin / gearratio)-(10.0*2.75*deg2rad); // Angle of motor shaft in rad + correctie voor q1
    omega2 = deltaCounts2 / Ts * factorin / gearratio; // Angular velocity of motor shaft in rad/s
    motor2error=motor2ref-motor2angle;
    if (controlsignal2<0) {
        motordir2= 0;
    } else {
        motordir2= 1;
    }
    if (motor_calibration_done == true) {
        motor2Power.write(abs(controlsignal2));
    }
    motor2Direction= motordir2;
}

/*
------------------------------ MOTOR SUBSTATE FUNCTIONS ------------------------------
*/

void do_motor_wait()
{
    // Entry function
    if ( motor_state_changed == true ) {
        motor_state_changed = false;
        // More functions
    }

    PID_controller();
    motorControl();

    // State transition guard
    if ( button2_pressed ) {
        button2_pressed = false;
        motor_curr_state = motor_encoderset;           //Beginnen met calibratie
        motor_state_changed = true;
        // More functions
    }

}

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_calibration_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;
    }

}

/*
------------------------------ 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 emg1_out_prev;
double emg1_dt; //delete
double emg1_dt_prev;
double emg1_dtdt; //delete

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;
int emg3_cal_size;//delete
int emg3_dir = 1;

/*
------------------------------ 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;
BiQuadChain bqc1_notch;
BiQuadChain bqc2_notch;
BiQuadChain bqc3_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;
BiQuadChain bqc1_high;
BiQuadChain bqc2_high;
BiQuadChain bqc3_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;
BiQuadChain bqc1_low;
BiQuadChain bqc2_low;
BiQuadChain bqc3_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 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
    }

    // Do stuff until end condition is met
    // Set HIDScope outputs
    scope.set(0, emg1 );
    scope.set(1, emg1_env );
    scope.set(2, emg2 );
    scope.set(3, emg2_env );
    //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);

                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);
                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);

        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


        // ------- TO DO: MAKE SURE THESE BUTTONS DO NOT BOUNCE (e.g. with button1.rise() ) ------
        //button1.fall( &toggleEMG1Dir ); // Change to state MVC calibration on button1 press
        //button2.fall( &toggleEMG2Dir ); // Change to state rest calibration on button2 press

    }

    // 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 SUBSTATE MACHINE ------------------------------
*/

void motor_state_machine()
{
    switch(motor_curr_state) {
        case motor_wait:
            do_motor_wait();
            break;
        case motor_encoderset:
            do_motor_Encoder_Set();
            break;
        case motor_finish:
            do_motor_finish();
            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
    motor1Power.write(0.0f);
    motor2Power.write(0.0f);
    Vx=0.0f;
    Vy=0.0f;

    // 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
    doStuff();

    // 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
    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

    emg1_out_prev = emg1_out; // Set previous emg_out signal
    emg1_dt_prev = emg1_dt; // Set previous emg_out_dt signal
    
    if (button1_pressed) {
        button1_pressed = false;
        emg1_dir = emg1_dir * -1.0;
    }
    
    if (button2_pressed) {
        button2_pressed = false;
        emg2_dir = emg2_dir * -1.0;
    }

    // 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);
    }
    emg1_dt = (emg1_out - emg1_out_prev) / Ts; // Calculate derivative of filtered normalized output signal
    emg1_dtdt = (emg1_dt - emg1_dt_prev) / Ts; // Calculate acceleration of filtered normalized output signal
    Vx = emg1_out * 15.0f * emg1_dir;

    // 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);
    }
    Vy = emg2_out * 15.0f * emg2_dir;

    // Idem for emg3
    if ( emg3_norm < emg3_th ) {
        emg3_out = 0.0;
    } else if ( emg3_norm > 1.0f ) {
        emg3_out = 1.0;
    } else {
        emg3_out = rescale(emg3_norm, 0, 1, emg3_th, 1);
    }
    
    /*
    // For testing Vx and Vy
    static float t=0;
    Vy=10.0f*sin(1.0f*t);
    Vx=0.0f;
    t+=Ts;
    */
    
    // Move motors
    PID_controller();
    motorControl();
    RKI();

    // Set HIDScope outputs
    scope.set(0, emg1 );
    scope.set(1, Vx );
    scope.set(2, emg2 );
    scope.set(3, Vy );
    //scope.set(2, emg2_out );
    //scope.set(3, emg3_out );
    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();

        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)

        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
            // emg1_cal_size = emg1_cal.size(); // Used for debugging
            emg2_cal.push_back(emg2_env); // Add values to calibration vector
            // emg2_cal_size = emg1_cal.size(); // Used for debugging
            emg3_cal.push_back(emg3_env); // Add values to calibration vector
            // emg3_cal_size = emg1_cal.size(); // Used for debugging
        }
    }

    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();
    // 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 );

    // ---------- Attach buttons ----------
    button1.fall( &button1Press );
    button2.fall( &button2Press );
    switch2.fall( &switch2Press );
    switch3.fall( &switch3Press );
    
    // ---------- 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 substate: %i Motor substate: %i\r\n", global_curr_state, emg_curr_state, motor_curr_state);
        pc.printf("EMG1 direction: %f EMG2 direction: %f \r\n", emg1_dir, emg2_dir);
        pc.printf("Vx: %f Vy: %f \r\n", Vx, Vy);
        pc.printf("q1: %f q2: %f \r\n",q1*rad2deg,q2*rad2deg);
        pc.printf("Xe: %f Ye: %f\r\n",xe,ye);
        wait(0.5f);
    }
}