Control up to two motors using filtered EMG signals and a PID controller

Dependencies:   FastPWM HIDScope MODSERIAL QEI Matrix biquadFilter controller errorFetch mbed motorConfig refGen MatrixMath inverseKinematics

Fork of Minor_test_serial by First Last

main.cpp

Committer:
tvlogman
Date:
2017-09-21
Revision:
15:b76b8cff4d8f
Parent:
14:664870b5d153
Child:
16:27430afe663e

File content as of revision 15:b76b8cff4d8f:

#include "mbed.h"
#include "MODSERIAL.h"
#include "HIDScope.h"
#include "QEI.h"
#include "FastPWM.h"

enum robotStates {KILLED, ACTIVE};
robotStates currentState = KILLED;

QEI Encoder(D12,D13,NC,64, QEI::X4_ENCODING);
MODSERIAL pc(USBTX, USBRX);

// Defining outputs
DigitalOut motor1_direction(D4);
PwmOut motor1_pwm(D5);

// Defining inputs
InterruptIn sw2(SW2);
InterruptIn sw3(SW3);
AnalogIn pot(A0);

// Enabling motors
bool motorsOn = true;


float pwmPeriod = 1.0/5000.0;

Ticker encoderTicker;
volatile int counts = 0;
volatile float revs = 0.00;

void readEncoder(){
    counts = Encoder.getPulses();
    revs = counts/64.0f;
    pc.printf("%i pulses \r\n", counts);
    pc.printf("%f revolutions \r\n", revs);
    }
    
void killSwitch(){
    pc.printf("Motors turned off");
    currentState = KILLED;
    }
    
void turnMotorsOn(){
    pc.printf("Motors turned on");
    currentState = ACTIVE; 
    }

    
void M1switchDirection(){
    motor1_direction = !motor1_direction;
    }

int frequency_pwm = 10000; //10kHz PWM

int main()
    {
    motor1_direction = false;
    motor1_pwm.period(pwmPeriod);//T=1/f 
    sw2.fall(&killSwitch);
    sw3.fall(&turnMotorsOn);
    pc.baud(115200);
    encoderTicker.attach(readEncoder, 1.0);
      
    pc.printf("Encoder ticker attached and baudrate set");
    
    while(true){
            switch(currentState){
                case KILLED:
                    motor1_pwm.write(0.0);
                    break;
                case ACTIVE:
                    motor1_pwm.write(pot.read()); // Motor speed proportional to pot meter                
                    break;
            }  
        }
    
    }