UVic Assistive Technology Lab / Mbed 2 deprecated DSLR_Camera_Gimbal

Dependencies:   mbed ros_lib_kinetic

Committer:
MikeGray92
Date:
Mon Mar 05 23:08:34 2018 +0000
Revision:
4:89ebfa37663b
Parent:
3:527f0b949839
Child:
6:2ffa254e8f6e
Added chat modes; Defined new limits for gimbal

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>
MikeGray92 3:527f0b949839 7 #include "mbed.h"
MikeGray92 2:0537a8007a39 8
group-UVic-Assistive-Technolog 0:3a767f41cf04 9 // Initializations
group-UVic-Assistive-Technolog 0:3a767f41cf04 10
group-UVic-Assistive-Technolog 0:3a767f41cf04 11 void setupGimbal(){
group-UVic-Assistive-Technolog 0:3a767f41cf04 12 gimbal.servo(YAWID, YAWZERO, 50); // Set the Gimbal at the zero position.
group-UVic-Assistive-Technolog 0:3a767f41cf04 13 control.yaw = YAWZERO;
group-UVic-Assistive-Technolog 0:3a767f41cf04 14 wait(0.1);
group-UVic-Assistive-Technolog 0:3a767f41cf04 15 gimbal.servo(PITCHID, PITCHZERO, 50);
group-UVic-Assistive-Technolog 0:3a767f41cf04 16 control.pitch = PITCHZERO;
group-UVic-Assistive-Technolog 0:3a767f41cf04 17 wait(0.1);
group-UVic-Assistive-Technolog 0:3a767f41cf04 18 gimbal.servo(ROLLID, ROLLZERO, 50);
group-UVic-Assistive-Technolog 0:3a767f41cf04 19 control.roll = ROLLZERO;
group-UVic-Assistive-Technolog 0:3a767f41cf04 20 }
group-UVic-Assistive-Technolog 0:3a767f41cf04 21
group-UVic-Assistive-Technolog 0:3a767f41cf04 22 void setupLift(){
group-UVic-Assistive-Technolog 0:3a767f41cf04 23
MikeGray92 4:89ebfa37663b 24 startHallInt();
group-UVic-Assistive-Technolog 0:3a767f41cf04 25 liftSpeed.period_us(50);
group-UVic-Assistive-Technolog 0:3a767f41cf04 26
group-UVic-Assistive-Technolog 0:3a767f41cf04 27 // Find the bottom position. Go down at lowest speed and set zero point.
group-UVic-Assistive-Technolog 0:3a767f41cf04 28 liftDirection.write(LIFTDOWN);
group-UVic-Assistive-Technolog 0:3a767f41cf04 29 liftSpeed.write(0.3);
group-UVic-Assistive-Technolog 0:3a767f41cf04 30
group-UVic-Assistive-Technolog 0:3a767f41cf04 31 // Wait until the motor stalls, know the motor is at bottom.
MikeGray92 4:89ebfa37663b 32 while(stallcount < 3){wait(.01);}
MikeGray92 4:89ebfa37663b 33 liftSpeed.write(0);
MikeGray92 4:89ebfa37663b 34 currentPosition = 0;
MikeGray92 4:89ebfa37663b 35 stopHallInt();
MikeGray92 4:89ebfa37663b 36 wait(0.1);
MikeGray92 4:89ebfa37663b 37 liftDirection.write(LIFTUP);
MikeGray92 4:89ebfa37663b 38 liftSpeed.write(0.3);
MikeGray92 4:89ebfa37663b 39 wait(0.1);
MikeGray92 4:89ebfa37663b 40 liftSpeed.write(0);
group-UVic-Assistive-Technolog 0:3a767f41cf04 41 }
group-UVic-Assistive-Technolog 0:3a767f41cf04 42
group-UVic-Assistive-Technolog 0:3a767f41cf04 43 void setupROSNode(ros::NodeHandle& nh, ros::Subscriber<std_msgs::Float32MultiArray>& sub){
group-UVic-Assistive-Technolog 0:3a767f41cf04 44
group-UVic-Assistive-Technolog 0:3a767f41cf04 45 nh.getHardware()->setBaud(57600);
group-UVic-Assistive-Technolog 0:3a767f41cf04 46 nh.initNode();
group-UVic-Assistive-Technolog 0:3a767f41cf04 47 nh.subscribe(sub);
group-UVic-Assistive-Technolog 0:3a767f41cf04 48 }
MikeGray92 4:89ebfa37663b 49
MikeGray92 4:89ebfa37663b 50 void startHallInt() {
MikeGray92 4:89ebfa37663b 51 hallInt.attach(&hallInterrupt, 0.03);
MikeGray92 4:89ebfa37663b 52 }
group-UVic-Assistive-Technolog 0:3a767f41cf04 53
MikeGray92 4:89ebfa37663b 54 void stopHallInt() {
MikeGray92 4:89ebfa37663b 55 hallInt.detach();
MikeGray92 4:89ebfa37663b 56 }
MikeGray92 4:89ebfa37663b 57