2 losse EMG signalen van de biceps en deltoid

Dependencies:   HIDScope MODSERIAL mbed-dsp mbed Encoder

Fork of Lampje_EMG_Gr6 by Jesse Kaiser

main.cpp

Committer:
irisl
Date:
2014-11-01
Revision:
25:a12d51345aa4
Parent:
24:a61c2cadbd36
Child:
26:9859a71456fd

File content as of revision 25:a12d51345aa4:

#include "mbed.h"
#include "HIDScope.h"
#include "arm_math.h"
#include "MODSERIAL.h"
#include "encoder.h"
#include "PwmOut.h"

#define TSAMP 0.005
#define K_P1 (3.5) //voor motor1 is het 3.5
#define K_I1 (0.01  *TSAMP) //voor motor1 is het 0.01
#define K_P2 (0.7)
#define K_I2 (0.01 *TSAMP)
#define I_LIMIT 1.
//#define PI 3.14159265
#define l_arm 0.5

#define M1_PWM PTC8
#define M1_DIR PTC9
#define M2_PWM PTA5
#define M2_DIR PTA4

//Groene kabel moet op de GROUND en blauw op de 3.3v aansluiting

Serial pc(USBTX, USBRX);

DigitalOut myledred(PTB3);
DigitalOut myledgreen(PTB1);
DigitalOut myledblue(PTB2);

//Define objects
AnalogIn    emg0(PTB0); //Analog input
AnalogIn    emg1(PTC2); //Analog input
HIDScope scope(4);

//motor 25D
Encoder motor1(PTD3,PTD5); //wit, geel
PwmOut pwm_motor1(M2_PWM);
DigitalOut motordir1(M2_DIR);

//motor2 37D
Encoder motor2(PTD2, PTD0); //wit, geel
PwmOut pwm_motor2(M1_PWM);
DigitalOut motordir2(M1_DIR);

float pwm1_percentage = 0;
float pwm2_percentage = 0;
int cur_pos_motor1;
int prev_pos_motor1 = 0;
int cur_pos_motor2;
int prev_pos_motor2 = 0;
float speed1_rad;
float speed2_rad;
float pos_motor1_rad;
float pos_motor2_rad;
int staat1 = 0;
int staat2 = 0;
volatile float arm_hoogte = 0;
volatile float batje_hoek = 0;
int wait_iterator1 = 0;
int wait_iterator2 = 0;


// EMG

arm_biquad_casd_df1_inst_f32 lowpass_biceps;
arm_biquad_casd_df1_inst_f32 lowpass_deltoid;
//lowpass filter settings: Fc = 5 Hz, Fs = 500 Hz, Gain = -3 dB
float lowpass_const[] = {0.0009446914586925257, 0.0018893829173850514, 0.0009446914586925257, 1.911196288237583, -0.914975054072353};
//state values
float lowpass_biceps_states[4];
float lowpass_deltoid_states[4];
arm_biquad_casd_df1_inst_f32 highnotch_biceps;
arm_biquad_casd_df1_inst_f32 highnotch_deltoid;
//highpass filter settings: Fc = 20 Hz, Fs = 500 Hz, Gain = -3 dB, notch Fc = 50, Fs =500Hz, Gain = -3 dB
float highnotch_const[] = {0.9149684297741606, -1.8299368595483212, 0.9149684297741606, 1.8226935021735358, -0.8371802169231065 ,0.969531252908746, -1.18733334554802E-16, 0.969531252908746, -1.18733334554802E-16, 0.939062505817492};
//state values
float highnotch_biceps_states[8];
float highnotch_deltoid_states[8];

//De globale variabele voor het gefilterde EMG signaal
float filtered_biceps;
float filtered_deltoid;
float filtered_average_bi;
float filtered_average_del;


void average_biceps(float filtered_biceps,float *average)
{
    static float total=0;
    static float number=0;
    total = total + filtered_biceps;
    number = number + 1;
    if ( number == 500) {
        *average = total/500;
        total = 0;
        number = 0;
    }
}

void average_deltoid(float filtered_input,float *average_output)
{
    static float total=0;
    static float number=0;
    total = total + filtered_input;
    number = number + 1;
    if ( number == 500) {
        *average_output = total/500;
        total = 0;
        number = 0;
    }
}

/** Looper function
* functions used for Ticker and Timeout should be of type void <name>(void)
* i.e. no input arguments, no output arguments.
* if you want to change a variable that you use in other places (for example in main)
* you will have to make that variable global in order to be able to reach it both from
* the function called at interrupt time, and in the main function.
* To make a variable global, define it under the includes.
* variables that are changed in the interrupt routine (written to) should be made
* 'volatile' to let the compiler know that those values may change outside the current context.
* i.e.: "volatile uint16_t emg_value;" instead of "uint16_t emg_value"
* in the example below, the variable is not re-used in the main function, and is thus declared
* local in the looper function only.
**/


void looper()
{
    /*variable to store value in*/
    uint16_t emg_value1;
    uint16_t emg_value2;

    float emg_value1_f32;
    float emg_value2_f32;
    /*put raw emg value both in red and in emg_value*/
    emg_value1 = emg0.read_u16(); // read direct ADC result, converted to 16 bit integer (0..2^16 = 0..65536 = 0..3.3V)
    emg_value1_f32 = emg0.read();

    emg_value2 = emg1.read_u16();
    emg_value2_f32 = emg1.read();

    //process emg biceps
    arm_biquad_cascade_df1_f32(&highnotch_biceps, &emg_value1_f32, &filtered_biceps, 1 );
    filtered_biceps = fabs(filtered_biceps);
    arm_biquad_cascade_df1_f32(&lowpass_biceps, &filtered_biceps, &filtered_biceps, 1 );
    average_biceps(filtered_biceps,&filtered_average_bi);
    //process emg deltoid
    arm_biquad_cascade_df1_f32(&highnotch_deltoid, &emg_value2_f32, &filtered_deltoid, 1 );
    filtered_deltoid = fabs(filtered_deltoid);
    arm_biquad_cascade_df1_f32(&lowpass_deltoid, &filtered_deltoid, &filtered_deltoid, 1 );
    average_deltoid(filtered_deltoid, &filtered_average_del);

    /*send value to PC. */
    //scope.set(0,emg_value1);     //Raw EMG signal biceps
    //scope.set(1,emg_value2);    //Raw EMG signal Deltoid
    scope.set(0,filtered_biceps);  //processed float biceps
    scope.set(1,filtered_average_bi); //processed float deltoid
    scope.set(2,filtered_deltoid);  //processed float biceps
    scope.set(3,filtered_average_del); //processed float deltoid
    scope.send();

}

// LED AANSTURING

Ticker ledticker;


void BlinkRed(int n)
{
    for (int i=0; i<n; i++) {
        myledred = 0;
        myledgreen = 0;
        myledblue = 0;
        wait(0.1);
        myledred = 1;
        myledgreen = 0;
        myledblue = 0;
        wait(0.1);
    }
}

void greenblink()
{
    if(myledgreen.read())
        myledgreen = 0;
    else
        myledgreen = 1;
}

void BlinkGreen()
{
    myledred= 0;
    myledblue =0;
    ledticker.attach(&greenblink,.5);
    /*  myled1 = 1;
      myled2 = 1;
      myled3 = 1;
      wait(0.1);
      myled1 = 0;
      myled2 = 1;
      myled3 = 1;
      wait(0.1);*/
}

void stopblinkgreen()
{
    ledticker.detach();
}


void BlinkGreen1 ()
{

    myledred = 0;
    myledgreen = 0;
    myledblue = 0;
    wait(0.1);
    myledred = 0;
    myledgreen = 1;
    myledblue = 0;
    wait(0.1);
}


void BlinkBlue(int n)
{
    for (int i=0; i<n; i++) {
        myledred = 0;
        myledgreen = 0;
        myledblue = 0;
        wait(0.1);
        myledred = 0;
        myledgreen = 0;
        myledblue = 1;
        wait(0.1);
    }
}

void ShineGreen ()
{
    myledred = 0;
    myledgreen = 1;
    myledblue = 0;
}

void ShineBlue ()
{
    myledred = 0;
    myledgreen = 0;
    myledblue = 1;
}

void ShineRed ()
{
    myledred = 1;
    myledgreen = 0;
    myledblue = 0;
}

// MOTORFUNCTIES

void clamp(float* in, float min, float max) // "*" is een pointer (verwijst naar het adres waar een variabele instaat). Dus je slaat niet de variabele op
// maar de locatie van de variabele.
{
*in > min ? /*(*/*in < max? /*niets doen*/ : *in = max/*)*/: *in = min; // a ? b : c --> als a waar is, dan doe je b, en anders c
    // *in = het getal dat staat op locatie van in --> waarde van new_pwm
}

float pid1(float setpoint1, float measurement1)
{
    float error1;
    float           out_p1 = 0;
    static float    out_i1 = 0;
    error1  = (setpoint1 - measurement1);
    out_p1  = error1*K_P1;
    out_i1 += error1*K_I1;
    clamp(&out_i1,-I_LIMIT,I_LIMIT);
    return out_p1 + out_i1;
}

float pid2(float setpoint2, float measurement2)
{
    float error2;
    float           out_p2 = 0;
    static float    out_i2 = 0;
    error2  = (setpoint2 - measurement2);
    out_p2  = error2*K_P2;
    out_i2 += error2*K_I2;
    clamp(&out_i2,-I_LIMIT,I_LIMIT);
    return out_p2 + out_i2;
}
float prev_setpoint1 = 0;
float setpoint1 = 0;
float prev_setpoint2 = 0;
float setpoint2 = 0;

void batje_links ()
{
    speed1_rad = -1.0; //positief is CCW, negatief CW (boven aanzicht)
    setpoint1 = prev_setpoint1 + TSAMP * speed1_rad;
    if(setpoint1 > (11.3*2.3*2.0*PI/360)) { //setpoint in graden
        setpoint1 = (11.3*2.3*2.0*PI/360);
    }
    if(setpoint1 < -(11.3*2.3*2.0*PI/360)) {
        setpoint1 = -(11.3*2.3*2.0*PI/360);
    }
    prev_setpoint1 = setpoint1;
}

void batje_rechts ()
{
    speed1_rad = 1.0; //positief is CCW, negatief CW (boven aanzicht)
    setpoint1 = prev_setpoint1 + TSAMP * speed1_rad;
    if(setpoint1 > (11.3*2.3*2.0*PI/360)) { //setpoint in graden
        setpoint1 = (11.3*2.3*2.0*PI/360);
    }
    if(setpoint1 < -(11.3*2.3*2.0*PI/360)) {
        setpoint1 = -(11.3*2.3*2.0*PI/360);
    }
    pwm_motor1.write(abs(pwm1_percentage));
    prev_setpoint1 = setpoint1;
    if(setpoint1 >= (11.3*2.3*2.0*PI/360)-0.1) {
        staat1 = 1;
    }
}


void batje_begin_links ()
{
    speed1_rad = 1.0; //positief is CCW, negatief CW (boven aanzicht)
    setpoint1 = prev_setpoint1 + TSAMP * speed1_rad;
    if(setpoint1 > (0*2.3*2.0*PI/360)) { //setpoint in graden
        setpoint1 = (0*2.3*2.0*PI/360);
    }
    if(setpoint1 < -(0*2.3*2.0*PI/360)) {
        setpoint1 = -(0*2.3*2.0*PI/360);
    }
    prev_setpoint1 = setpoint1;
}

void batje_begin_rechts ()
{
    speed1_rad = -1.0; //positief is CCW, negatief CW (boven aanzicht)
    setpoint1 = prev_setpoint1 + TSAMP * speed1_rad;
    if(setpoint1 > (0*2.3*2.0*PI/360)) { //setpoint in graden
        setpoint1 = (0*2.3*2.0*PI/360);
    }
    if(setpoint1 < -(0.0*2.3*2.0*PI/360)) {
        setpoint1 = -(0.0*2.3*2.0*PI/360);
    }
    prev_setpoint1 = setpoint1;
}

void arm_hoog () //LET OP, PAS VARIABELE NOG AAN DIT IS VOOR TESTEN
{
    speed2_rad = 6.0; //positief is CCW, negatief CW (boven aanzicht)
    setpoint2 = prev_setpoint2 + TSAMP * speed2_rad;
    if(setpoint2 > (155.0*2.0*PI/360)) { //setpoint in graden
        setpoint2 = (155.0*2.0*PI/360);
    }
    if(setpoint2 < -(155.0*2.0*PI/360)) {
        setpoint2 = -(155.0*2.0*PI/360);
    }
    prev_setpoint2 = setpoint2;
    if(setpoint2 >= (155.0*2.0*PI/360)-0.1) {
        staat2 = 1;
    }
}

void arm_mid ()
{
    speed2_rad = 4.0; //positief is CCW, negatief CW (boven aanzicht)
    setpoint2 = prev_setpoint2 + TSAMP * speed2_rad;
    if(setpoint2 > (155.0*2.0*PI/360)) { //setpoint in graden
        setpoint2 = (155.0*2.0*PI/360);
    }
    if(setpoint2 < -(155.0*2.0*PI/360)) {
        setpoint2 = -(155.0*2.0*PI/360);
    }
    prev_setpoint2 = setpoint2;
    if(setpoint2 >= (155.0*2.0*PI/360)-0.1) {
        staat2 = 1;
    }
}

void arm_laag ()
{
    speed2_rad = 2.0; //positief is CCW, negatief CW (boven aanzicht)
    setpoint2 = prev_setpoint2 + TSAMP * speed2_rad;
    if(setpoint2 > (155*2.0*PI/360)) { //setpoint in graden
        setpoint2 = (155*2.0*PI/360);
    }
    if(setpoint2 < -(155.0*2.0*PI/360)) {
        setpoint2 = -(155.0*2.0*PI/360);
    }
    prev_setpoint2 = setpoint2;
    if(setpoint2 >= (155.0*2.0*PI/360)-0.1) {
        staat2 = 1;
    }
}

void arm_begin ()
{
    speed2_rad = -1.0; //positief is CCW, negatief CW (boven aanzicht)
    setpoint2 = prev_setpoint2 + TSAMP * speed2_rad;
    if(setpoint2 > (0.0*2.0*PI/360)) { //setpoint in graden
        setpoint2 = (0.0*2.0*PI/360);
    }
    if(setpoint2 < -(0.0*2.0*PI/360)) {
        setpoint2 = -(0.0*2.0*PI/360);
    }
    prev_setpoint2 = setpoint2;
}

void looper_motor()
{
    //MOTOR1
    pc.printf("%d \r\n", motor1.getPosition());
    cur_pos_motor1 = motor1.getPosition();
    pos_motor1_rad = (float)cur_pos_motor1/(4128.0/(2.0*PI)); //moet 4128
    pwm1_percentage = pid1(setpoint1, pos_motor1_rad);
    if (pwm1_percentage < -1.0) {
        pwm1_percentage = -1.0;
    }
    if (pwm1_percentage > 1.0) {
        pwm1_percentage = 1.0;
    }
    pwm_motor1.write(abs(pwm1_percentage));
    if(pwm1_percentage > 0) {
        motordir1 = 0;
    } else {
        motordir1 = 1;
    }

    //MOTOR2
    cur_pos_motor2 = motor2.getPosition();
    pos_motor2_rad = (float)cur_pos_motor2/(3200.0/(2.0*PI));
    pwm2_percentage = pid2(setpoint2, pos_motor2_rad); //
    if (pwm2_percentage < -1.0) {
        pwm2_percentage = -1.0;
    }
    if (pwm2_percentage > 1.0) {
        pwm2_percentage = 1.0;
    }
    pwm_motor2.write(abs(pwm2_percentage));
    if(pwm2_percentage > 0) {
        motordir2 = 0;
    } else {
        motordir2 = 1;
    }


    //STATES

    if (batje_hoek == 1) {
        if(staat1 == 0) {
            batje_rechts();
            wait_iterator1 = 0;
        } else if(staat1 ==1) {
            wait_iterator1++;
            if(wait_iterator1 > 1000)
                staat1 = 2;
        } else {
            batje_begin_rechts();
        }
    }

    if (batje_hoek == 2) {
        if(staat1 == 0) {
            batje_links();
            wait_iterator1 = 0;
        } else if(staat1 ==1) {
            wait_iterator1++;
            if(wait_iterator1 > 1000)
                staat1 = 2;
        } else {
            batje_begin_links ();
        }
    }


    if(arm_hoogte == 1) {
        if(staat2 == 0) {
            arm_laag();
            wait_iterator2 = 0;
        } else if(staat2 == 1) {
            wait_iterator2++;
            if(wait_iterator2 > 400)
                staat2 = 2;
        } else {
            arm_begin();
        }
    }
    if(arm_hoogte == 2) {
        if(staat2 == 0) {
            arm_mid();
            wait_iterator2 = 0;
        } else if(staat2 == 1) {
            wait_iterator2++;
            if(wait_iterator2 > 400)
                staat2 = 2;
        } else {
            arm_begin();
        }
    }
    if(arm_hoogte == 3) {
        if(staat2 == 0) {
            arm_hoog();
            wait_iterator2 = 0;
        } else if(staat2 == 1) {
            wait_iterator2++;
            if(wait_iterator2 > 400)
                staat2 = 2;
        } else {
            arm_begin();
        }
    }
}

int main()
{

    pwm_motor1.period_us(100);
    motor1.setPosition(0);
    pwm_motor2.period_us(100);
    motor2.setPosition(0);
    pc.baud(115200);

    Ticker log_timer;
    //set up filters. Use external array for constants
    arm_biquad_cascade_df1_init_f32(&lowpass_biceps,1 , lowpass_const, lowpass_biceps_states);
    arm_biquad_cascade_df1_init_f32(&lowpass_deltoid,1 , lowpass_const, lowpass_deltoid_states);
    arm_biquad_cascade_df1_init_f32(&highnotch_biceps,2 ,highnotch_const,highnotch_biceps_states);
    arm_biquad_cascade_df1_init_f32(&highnotch_deltoid,2 ,highnotch_const,highnotch_deltoid_states);
    /**Here you attach the 'void looper(void)' function to the Ticker object
    * The looper() function will be called every 0.01 seconds.
    * Please mind that the parentheses after looper are omitted when using attach.
    */
    log_timer.attach(looper, 0.001);

    Ticker looptimer;
    looptimer.attach(looper_motor,TSAMP);
    while(1) { //Loop
        /*Empty!*/
        /*Everything is handled by the interrupt routine now!*/

        while(1) {
            pc.printf("Span de biceps aan om het instellen te starten.\n");
            do {
                ShineRed();
            } while(filtered_average_bi < 0.05 && filtered_average_del <0.05); // In rust, geen meting
            if (filtered_average_bi > 0.05) {
                BlinkRed(10);
                BlinkGreen();
                while (1) {
                    pc.printf("In de loop.\n");
                    if (filtered_average_bi > 0.05 && filtered_average_del > 0.05) {
                        stopblinkgreen();
                        pc.printf("ShineGreen.\n");
                        ShineGreen();
                        wait (4);
                        break;
                    }
                    if (filtered_average_bi < 0.05 && filtered_average_del > 0.05) {
                        stopblinkgreen();
                        pc.printf("ShineBlue.\n");
                        ShineBlue();
                        batje_hoek = 2;
                        wait(4);
                        break;
                    } else if (filtered_average_bi > 0.05 && filtered_average_del < 0.05)

                    {
                        stopblinkgreen();
                        pc.printf("ShineRed.\n");
                        ShineRed();
                        batje_hoek = 1;
                        wait (4);
                        break;
                    }
                }
                BlinkGreen();
                while (1) {
                    pc.printf("In de loop.\n");
                    if (filtered_average_bi > 0.05 && filtered_average_del > 0.05) {
                        stopblinkgreen();
                        pc.printf("ShineGreen.\n");
                        ShineGreen();
                        arm_hoogte = 3;
                        wait (4);
                        break;
                    }
                    if (filtered_average_bi < 0.05 && filtered_average_del > 0.05) {
                        stopblinkgreen();
                        pc.printf("ShineBlue.\n");
                        ShineBlue();
                        arm_hoogte = 1;
                        wait(4);
                        break;
                    } else if (filtered_average_bi > 0.05 && filtered_average_del < 0.05)

                    {
                        stopblinkgreen();
                        pc.printf("ShineRed.\n");
                        ShineRed();
                        arm_hoogte = 2;
                        wait (4);
                        break;
                    }
                }
                batje_hoek = 0;
                arm_hoogte = 0;
            }

        }
    }
}