UVic Assistive Technology Lab / Mbed 2 deprecated DSLR_Camera_Gimbal

Dependencies:   mbed ros_lib_kinetic

lift.cpp

Committer:
MikeGray92
Date:
2018-02-08
Revision:
2:0537a8007a39
Parent:
1:1ac7d472cfa2
Child:
3:527f0b949839

File content as of revision 2:0537a8007a39:


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


void runLift(void){
    stallCheck();
    if (control.liftRun){
        // Set direction
        if(control.height > currentPosition){
            liftDirection.write(LIFTUP);    
        }
        else if(control.height < currentPosition){
            liftDirection.write(LIFTDOWN);
        }
        // Check if arrived at destination height.
//        if (abs(control.height - currentPosition) < 5){ 
//            control.liftRun = false;
//            liftSpeed.write(0);
//        }
        if (control.height == currentPosition){ 
            control.liftRun = false;
            liftSpeed.write(0);
        }
        else {
            liftSpeed.write(0.5);
        }       
    }    
}

void stallCheck(void){
    if(stall && liftSpeed.read() > 0){
        stall = false;
        control.liftRun = false;
        liftSpeed.write(0);
        if (liftDirection.read() == LIFTUP){
            currentPosition = LIFTHEIGHTMAX;
        }else{
            currentPosition = 0;
        }
    } 
}