UVic Assistive Technology Lab / Mbed 2 deprecated DSLR_Camera_Gimbal

Dependencies:   mbed ros_lib_kinetic

Committer:
MikeGray92
Date:
Tue Feb 06 20:50:55 2018 +0000
Revision:
1:1ac7d472cfa2
Parent:
0:3a767f41cf04
Child:
2:0537a8007a39
Set up with external interrupt for lift. NOT TESTED

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 rosInt.attach(&rosInterrupt, 0.1);
group-UVic-Assistive-Technolog 0:3a767f41cf04 24 }
group-UVic-Assistive-Technolog 0:3a767f41cf04 25
group-UVic-Assistive-Technolog 0:3a767f41cf04 26 void setupLift(){
group-UVic-Assistive-Technolog 0:3a767f41cf04 27
MikeGray92 1:1ac7d472cfa2 28 hallInt.attach(&hallInterrupt, 0.05);
MikeGray92 1:1ac7d472cfa2 29 liftInt.attach(&liftInterrupt, 0.1);
group-UVic-Assistive-Technolog 0:3a767f41cf04 30 liftSpeed.period_us(50);
group-UVic-Assistive-Technolog 0:3a767f41cf04 31
group-UVic-Assistive-Technolog 0:3a767f41cf04 32 // Find the bottom position. Go down at lowest speed and set zero point.
group-UVic-Assistive-Technolog 0:3a767f41cf04 33 liftDirection.write(LIFTDOWN);
group-UVic-Assistive-Technolog 0:3a767f41cf04 34 liftSpeed.write(0.3);
group-UVic-Assistive-Technolog 0:3a767f41cf04 35
group-UVic-Assistive-Technolog 0:3a767f41cf04 36 // Wait until the motor stalls, know the motor is at bottom.
MikeGray92 1:1ac7d472cfa2 37 while(!stall){}
MikeGray92 1:1ac7d472cfa2 38 if(stall == true){
MikeGray92 1:1ac7d472cfa2 39 liftSpeed.write(0);
MikeGray92 1:1ac7d472cfa2 40 currentPosition = 0;
MikeGray92 1:1ac7d472cfa2 41 stall = false;
MikeGray92 1:1ac7d472cfa2 42 }
group-UVic-Assistive-Technolog 0:3a767f41cf04 43 }
group-UVic-Assistive-Technolog 0:3a767f41cf04 44
group-UVic-Assistive-Technolog 0:3a767f41cf04 45 void setupROSNode(ros::NodeHandle& nh, ros::Subscriber<std_msgs::Float32MultiArray>& sub){
group-UVic-Assistive-Technolog 0:3a767f41cf04 46
group-UVic-Assistive-Technolog 0:3a767f41cf04 47 nh.getHardware()->setBaud(57600);
group-UVic-Assistive-Technolog 0:3a767f41cf04 48 nh.initNode();
group-UVic-Assistive-Technolog 0:3a767f41cf04 49 nh.subscribe(sub);
group-UVic-Assistive-Technolog 0:3a767f41cf04 50 }
group-UVic-Assistive-Technolog 0:3a767f41cf04 51
group-UVic-Assistive-Technolog 0:3a767f41cf04 52