UVic Assistive Technology Lab / Mbed 2 deprecated DSLR_Camera_Gimbal

Dependencies:   mbed ros_lib_kinetic

lift.cpp

Committer:
MikeGray92
Date:
2018-03-06
Revision:
6:2ffa254e8f6e
Parent:
4:89ebfa37663b
Child:
7:950b3c3b5a2b

File content as of revision 6:2ffa254e8f6e:


#include <stdint.h>
#include "mbed.h"
#include <ros.h>
#include <std_msgs/Empty.h>
#include <std_msgs/Float32MultiArray.h>
#include <BNO055.h>
#include <initializations.h>
#include <definitions.h>
#include <prototypes.h>
#include <Mx28.h>

bool startFlag = 0;

void runLift(void){
    stallCheck();
    //Check If Arrived
    if (abs(control.height - currentPosition) < 5){ 
        liftSpeed.write(0);
        stopHallInt();
        startFlag = 0;
    }
    else {
        if(startFlag == 0){
            startHallInt();
            startFlag = 1;
        }   
        // Set direction
        if(control.height > currentPosition){
            liftDirection.write(LIFTUP);   
        }
        else if(control.height < currentPosition){
            liftDirection.write(LIFTDOWN);
        }         
        liftSpeed.write(0.5);
    }  
}

//Determining if the lift stalled and stopping if it is
void stallCheck(void){
    if(stallcount > 3 && liftSpeed.read() > 0){
        liftSpeed.write(0);
        if (liftDirection.read() == LIFTUP){
            currentPosition = LIFTHEIGHTMAX;
            control.height = currentPosition;
        }else{
            currentPosition = 0;
            control.height = currentPosition;
        }
    } 
}