control for robotic arm that can play chess using a granular gripper

Dependencies:   Encoder mbed HIDScope Servo MODSERIAL

Fork of chessRobot by a steenbeek

main.cpp

Committer:
annesteenbeek
Date:
2015-10-20
Revision:
81:71e7e98deb2c
Parent:
79:cf500b63f349
Child:
86:a5f48ae7096e
Child:
96:f0ae582fa3e1
Child:
97:0f67952051e5

File content as of revision 81:71e7e98deb2c:

/*
   ________                      ____        __          __ 
  / ____/ /_  ___  __________   / __ \____  / /_  ____  / /_
 / /   / __ \/ _ \/ ___/ ___/  / /_/ / __ \/ __ \/ __ \/ __/
/ /___/ / / /  __(__  |__  )  / _, _/ /_/ / /_/ / /_/ / /_  
\____/_/ /_/\___/____/____/  /_/ |_|\____/_.___/\____/\__/  
                                                            
*/

#include "mbed.h"
#include "config.h"  // settings and pin configurations
#include "actuators.h"
#include "buttons.h"
#include "debug.h"
#include "emg.h"

Ticker switchesTick, debugTick, motorTick, EMGTick, safetyTick;
volatile bool switches_go=false, debug_go=false, motor_go=false, emg_go=false, safety_go=false;

void switches_activate(){switches_go=true;};
void debug_activate(){debug_go=true;};
void motor_activate(){motor_go=true;};
void emg_activate(){emg_go=true;};
void safety_activate(){safety_go=true;};

double motorCall = 0.01; // set motor frequency global so it can be used for speed.
int main(){
motorInit();    
calibrateMotors(); // start calibration procedure

switchesTick.attach(&switches_activate, 0.02f);
debugTick.attach(&debug_activate, 0.03f);
motorTick.attach(&motor_activate, motorCall);
EMGTick.attach(&emg_activate, 0.005f);
safetyTick.attach(&safety_activate, 0.001f);


    while (true) {
        if(safety_go){
            safety_go=false;
            safety();
        }
        if(emg_go){
            emg_go=false;
            readEMG();
        }
        if(switches_go){
            switches_go=false;
            checkSwitches();
        }
        if(debug_go){
            debug_go=false;
            debugProcess();
        }
        if(motor_go){
            motor_go=false;
            motorControl();
        // servoControl();
        }
    }
}