UVic Assistive Technology Lab / Mbed 2 deprecated DSLR_Camera_Gimbal

Dependencies:   mbed ros_lib_kinetic

initializations.cpp

Committer:
MikeGray92
Date:
2018-02-06
Revision:
1:1ac7d472cfa2
Parent:
0:3a767f41cf04
Child:
2:0537a8007a39

File content as of revision 1:1ac7d472cfa2:

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

#define BNO055_ID        (0xA0)

// Initializations

void setupGimbal(){
    gimbal.servo(YAWID, YAWZERO, 50); // Set the Gimbal at the zero position.
    control.yaw = YAWZERO;
    wait(0.1);
    gimbal.servo(PITCHID, PITCHZERO, 50);
    control.pitch = PITCHZERO;
    wait(0.1);
    gimbal.servo(ROLLID, ROLLZERO, 50);
    control.roll = ROLLZERO;
    dynaInt.attach(&motorInterrupt, 0.0001); // Update Dynamixel at 1kHz.
    rosInt.attach(&rosInterrupt, 0.1);
}

void setupLift(){
    
    hallInt.attach(&hallInterrupt, 0.05);
    liftInt.attach(&liftInterrupt, 0.1);
    liftSpeed.period_us(50);
    
    // Find the bottom position. Go down at lowest speed and set zero point.
    liftDirection.write(LIFTDOWN);
    liftSpeed.write(0.3);   
    
    // Wait until the motor stalls, know the motor is at bottom.
    while(!stall){}
    if(stall == true){
       liftSpeed.write(0);
       currentPosition = 0;
       stall = false; 
    } 
}

void setupROSNode(ros::NodeHandle& nh, ros::Subscriber<std_msgs::Float32MultiArray>& sub){
       
    nh.getHardware()->setBaud(57600);
    nh.initNode();
    nh.subscribe(sub);
}