UVic Assistive Technology Lab / Mbed 2 deprecated DSLR_Camera_Gimbal

Dependencies:   mbed ros_lib_kinetic

Committer:
MikeGray92
Date:
Wed Mar 14 19:33:08 2018 +0000
Revision:
7:950b3c3b5a2b
Parent:
6:2ffa254e8f6e
Child:
10:836e701d00a6
Tested with ROS; Added Initialized ROS Inputs to avoid errors at start up; Limit the roll movement, to allow greater pitch movement; In Bed Chatting mode changed to rosInput.mode = 4 and Standing Chatting mode changed to rosInput.mode = 2.

Who changed what in which revision?

UserRevisionLine numberNew contents of line
group-UVic-Assistive-Technolog 0:3a767f41cf04 1 #include <std_msgs/Empty.h>
MikeGray92 7:950b3c3b5a2b 2 #include <std_msgs/Int32MultiArray.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(){
MikeGray92 6:2ffa254e8f6e 12 // Set the Gimbal at the zero position.
MikeGray92 6:2ffa254e8f6e 13 gimbal.servo(YAWID, YAWZERO, 50);
group-UVic-Assistive-Technolog 0:3a767f41cf04 14 control.yaw = YAWZERO;
group-UVic-Assistive-Technolog 0:3a767f41cf04 15 wait(0.1);
group-UVic-Assistive-Technolog 0:3a767f41cf04 16 gimbal.servo(PITCHID, PITCHZERO, 50);
group-UVic-Assistive-Technolog 0:3a767f41cf04 17 control.pitch = PITCHZERO;
group-UVic-Assistive-Technolog 0:3a767f41cf04 18 wait(0.1);
group-UVic-Assistive-Technolog 0:3a767f41cf04 19 gimbal.servo(ROLLID, ROLLZERO, 50);
group-UVic-Assistive-Technolog 0:3a767f41cf04 20 control.roll = ROLLZERO;
group-UVic-Assistive-Technolog 0:3a767f41cf04 21 }
group-UVic-Assistive-Technolog 0:3a767f41cf04 22
group-UVic-Assistive-Technolog 0:3a767f41cf04 23 void setupLift(){
group-UVic-Assistive-Technolog 0:3a767f41cf04 24
MikeGray92 4:89ebfa37663b 25 startHallInt();
group-UVic-Assistive-Technolog 0:3a767f41cf04 26 liftSpeed.period_us(50);
group-UVic-Assistive-Technolog 0:3a767f41cf04 27
group-UVic-Assistive-Technolog 0:3a767f41cf04 28 // Find the bottom position. Go down at lowest speed and set zero point.
group-UVic-Assistive-Technolog 0:3a767f41cf04 29 liftDirection.write(LIFTDOWN);
group-UVic-Assistive-Technolog 0:3a767f41cf04 30 liftSpeed.write(0.3);
group-UVic-Assistive-Technolog 0:3a767f41cf04 31
group-UVic-Assistive-Technolog 0:3a767f41cf04 32 // Wait until the motor stalls, know the motor is at bottom.
MikeGray92 4:89ebfa37663b 33 while(stallcount < 3){wait(.01);}
MikeGray92 4:89ebfa37663b 34 liftSpeed.write(0);
MikeGray92 4:89ebfa37663b 35 currentPosition = 0;
MikeGray92 4:89ebfa37663b 36 stopHallInt();
group-UVic-Assistive-Technolog 0:3a767f41cf04 37 }
group-UVic-Assistive-Technolog 0:3a767f41cf04 38
MikeGray92 7:950b3c3b5a2b 39 void setupROSNode(ros::NodeHandle& nh, ros::Subscriber<std_msgs::Int32MultiArray>& sub){
group-UVic-Assistive-Technolog 0:3a767f41cf04 40 nh.getHardware()->setBaud(57600);
group-UVic-Assistive-Technolog 0:3a767f41cf04 41 nh.initNode();
group-UVic-Assistive-Technolog 0:3a767f41cf04 42 nh.subscribe(sub);
group-UVic-Assistive-Technolog 0:3a767f41cf04 43 }
MikeGray92 4:89ebfa37663b 44
MikeGray92 6:2ffa254e8f6e 45 void startHallInt() { // Starting hall effect timer interrupt
MikeGray92 4:89ebfa37663b 46 hallInt.attach(&hallInterrupt, 0.03);
MikeGray92 4:89ebfa37663b 47 }
group-UVic-Assistive-Technolog 0:3a767f41cf04 48
MikeGray92 6:2ffa254e8f6e 49 void stopHallInt() { // Stopping hall effect timer interrupt
MikeGray92 4:89ebfa37663b 50 hallInt.detach();
MikeGray92 4:89ebfa37663b 51 }