UVic Assistive Technology Lab / Mbed 2 deprecated DSLR_Camera_Gimbal

Dependencies:   mbed ros_lib_kinetic

Committer:
group-UVic-Assistive-Technolog
Date:
Wed Jan 31 05:24:12 2018 +0000
Revision:
0:3a767f41cf04
Child:
1:1ac7d472cfa2
Initial commit

Who changed what in which revision?

UserRevisionLine numberNew contents of line
group-UVic-Assistive-Technolog 0:3a767f41cf04 1 #include <std_msgs/Empty.h>
group-UVic-Assistive-Technolog 0:3a767f41cf04 2 #include <std_msgs/Float32MultiArray.h>
group-UVic-Assistive-Technolog 0:3a767f41cf04 3 #include <initializations.h>
group-UVic-Assistive-Technolog 0:3a767f41cf04 4 #include <ros.h>
group-UVic-Assistive-Technolog 0:3a767f41cf04 5 #include <definitions.h>
group-UVic-Assistive-Technolog 0:3a767f41cf04 6 #include <prototypes.h>
group-UVic-Assistive-Technolog 0:3a767f41cf04 7 #include "mbed.h"
group-UVic-Assistive-Technolog 0:3a767f41cf04 8
group-UVic-Assistive-Technolog 0:3a767f41cf04 9 #define BNO055_ID (0xA0)
group-UVic-Assistive-Technolog 0:3a767f41cf04 10
group-UVic-Assistive-Technolog 0:3a767f41cf04 11 // Initializations
group-UVic-Assistive-Technolog 0:3a767f41cf04 12
group-UVic-Assistive-Technolog 0:3a767f41cf04 13 void setupGimbal(){
group-UVic-Assistive-Technolog 0:3a767f41cf04 14 gimbal.servo(YAWID, YAWZERO, 50); // Set the Gimbal at the zero position.
group-UVic-Assistive-Technolog 0:3a767f41cf04 15 control.yaw = YAWZERO;
group-UVic-Assistive-Technolog 0:3a767f41cf04 16 wait(0.1);
group-UVic-Assistive-Technolog 0:3a767f41cf04 17 gimbal.servo(PITCHID, PITCHZERO, 50);
group-UVic-Assistive-Technolog 0:3a767f41cf04 18 control.pitch = PITCHZERO;
group-UVic-Assistive-Technolog 0:3a767f41cf04 19 wait(0.1);
group-UVic-Assistive-Technolog 0:3a767f41cf04 20 gimbal.servo(ROLLID, ROLLZERO, 50);
group-UVic-Assistive-Technolog 0:3a767f41cf04 21 control.roll = ROLLZERO;
group-UVic-Assistive-Technolog 0:3a767f41cf04 22 dynaInt.attach(&motorInterrupt, 0.0001); // Update Dynamixel at 1kHz.
group-UVic-Assistive-Technolog 0:3a767f41cf04 23
group-UVic-Assistive-Technolog 0:3a767f41cf04 24 rosInt.attach(&rosInterrupt, 0.1);
group-UVic-Assistive-Technolog 0:3a767f41cf04 25 }
group-UVic-Assistive-Technolog 0:3a767f41cf04 26
group-UVic-Assistive-Technolog 0:3a767f41cf04 27 void setupLift(){
group-UVic-Assistive-Technolog 0:3a767f41cf04 28
group-UVic-Assistive-Technolog 0:3a767f41cf04 29 int position = 0;
group-UVic-Assistive-Technolog 0:3a767f41cf04 30
group-UVic-Assistive-Technolog 0:3a767f41cf04 31 hallInt.attach(&hallInterrupt, 0.0001);
group-UVic-Assistive-Technolog 0:3a767f41cf04 32 liftSpeed.period_us(50);
group-UVic-Assistive-Technolog 0:3a767f41cf04 33
group-UVic-Assistive-Technolog 0:3a767f41cf04 34 // Find the bottom position. Go down at lowest speed and set zero point.
group-UVic-Assistive-Technolog 0:3a767f41cf04 35 liftDirection.write(LIFTDOWN);
group-UVic-Assistive-Technolog 0:3a767f41cf04 36 liftSpeed.write(0.3);
group-UVic-Assistive-Technolog 0:3a767f41cf04 37
group-UVic-Assistive-Technolog 0:3a767f41cf04 38 // Wait until the motor stalls, know the motor is at bottom.
group-UVic-Assistive-Technolog 0:3a767f41cf04 39 while(!stall){
group-UVic-Assistive-Technolog 0:3a767f41cf04 40 if (liftFlag){
group-UVic-Assistive-Technolog 0:3a767f41cf04 41 liftFlag = 0;
group-UVic-Assistive-Technolog 0:3a767f41cf04 42 checkLift(position, stall);
group-UVic-Assistive-Technolog 0:3a767f41cf04 43 }
group-UVic-Assistive-Technolog 0:3a767f41cf04 44 }
group-UVic-Assistive-Technolog 0:3a767f41cf04 45
group-UVic-Assistive-Technolog 0:3a767f41cf04 46 // Go up 0.3 cm from the bottom.
group-UVic-Assistive-Technolog 0:3a767f41cf04 47 liftDirection.write(LIFTUP);
group-UVic-Assistive-Technolog 0:3a767f41cf04 48 liftSpeed.write(0.3);
group-UVic-Assistive-Technolog 0:3a767f41cf04 49 position = 0;
group-UVic-Assistive-Technolog 0:3a767f41cf04 50 stall = FALSE;
group-UVic-Assistive-Technolog 0:3a767f41cf04 51 while(position < LIFTHEIGHTMIN){
group-UVic-Assistive-Technolog 0:3a767f41cf04 52 if (liftFlag){
group-UVic-Assistive-Technolog 0:3a767f41cf04 53 liftFlag = 0;
group-UVic-Assistive-Technolog 0:3a767f41cf04 54 checkLift(position, stall);
group-UVic-Assistive-Technolog 0:3a767f41cf04 55 }
group-UVic-Assistive-Technolog 0:3a767f41cf04 56 }
group-UVic-Assistive-Technolog 0:3a767f41cf04 57 liftSpeed.write(0);
group-UVic-Assistive-Technolog 0:3a767f41cf04 58 control.height = currentPosition;
group-UVic-Assistive-Technolog 0:3a767f41cf04 59 control.liftRun = FALSE;
group-UVic-Assistive-Technolog 0:3a767f41cf04 60 }
group-UVic-Assistive-Technolog 0:3a767f41cf04 61
group-UVic-Assistive-Technolog 0:3a767f41cf04 62 void setupROSNode(ros::NodeHandle& nh, ros::Subscriber<std_msgs::Float32MultiArray>& sub){
group-UVic-Assistive-Technolog 0:3a767f41cf04 63
group-UVic-Assistive-Technolog 0:3a767f41cf04 64 nh.getHardware()->setBaud(57600);
group-UVic-Assistive-Technolog 0:3a767f41cf04 65 nh.initNode();
group-UVic-Assistive-Technolog 0:3a767f41cf04 66 nh.subscribe(sub);
group-UVic-Assistive-Technolog 0:3a767f41cf04 67 }
group-UVic-Assistive-Technolog 0:3a767f41cf04 68
group-UVic-Assistive-Technolog 0:3a767f41cf04 69