UVic Assistive Technology Lab / Mbed 2 deprecated DSLR_Camera_Gimbal

Dependencies:   mbed ros_lib_kinetic

Committer:
MikeGray92
Date:
Thu Apr 26 18:33:11 2018 +0000
Revision:
10:836e701d00a6
Parent:
7:950b3c3b5a2b
Child:
13:8630f38f8066
Speed and Position controlled lift and gimbal

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;
MikeGray92 10:836e701d00a6 15 control.yawSpeed = 50;
MikeGray92 10:836e701d00a6 16 rosInput.yaw = YAWZERO;
MikeGray92 10:836e701d00a6 17 rosInput.yawSpeed = 50;
group-UVic-Assistive-Technolog 0:3a767f41cf04 18 wait(0.1);
group-UVic-Assistive-Technolog 0:3a767f41cf04 19 gimbal.servo(PITCHID, PITCHZERO, 50);
group-UVic-Assistive-Technolog 0:3a767f41cf04 20 control.pitch = PITCHZERO;
MikeGray92 10:836e701d00a6 21 control.pitchSpeed = 50;
MikeGray92 10:836e701d00a6 22 rosInput.pitch = PITCHZERO;
MikeGray92 10:836e701d00a6 23 rosInput.pitchSpeed = 50;
group-UVic-Assistive-Technolog 0:3a767f41cf04 24 wait(0.1);
group-UVic-Assistive-Technolog 0:3a767f41cf04 25 gimbal.servo(ROLLID, ROLLZERO, 50);
group-UVic-Assistive-Technolog 0:3a767f41cf04 26 control.roll = ROLLZERO;
MikeGray92 10:836e701d00a6 27 control.rollSpeed = 50;
MikeGray92 10:836e701d00a6 28 rosInput.roll = ROLLZERO;
MikeGray92 10:836e701d00a6 29 rosInput.rollSpeed = 50;
group-UVic-Assistive-Technolog 0:3a767f41cf04 30 }
group-UVic-Assistive-Technolog 0:3a767f41cf04 31
group-UVic-Assistive-Technolog 0:3a767f41cf04 32 void setupLift(){
group-UVic-Assistive-Technolog 0:3a767f41cf04 33
MikeGray92 4:89ebfa37663b 34 startHallInt();
group-UVic-Assistive-Technolog 0:3a767f41cf04 35 liftSpeed.period_us(50);
group-UVic-Assistive-Technolog 0:3a767f41cf04 36
group-UVic-Assistive-Technolog 0:3a767f41cf04 37 // Find the bottom position. Go down at lowest speed and set zero point.
group-UVic-Assistive-Technolog 0:3a767f41cf04 38 liftDirection.write(LIFTDOWN);
group-UVic-Assistive-Technolog 0:3a767f41cf04 39 liftSpeed.write(0.3);
group-UVic-Assistive-Technolog 0:3a767f41cf04 40
MikeGray92 10:836e701d00a6 41
group-UVic-Assistive-Technolog 0:3a767f41cf04 42 // Wait until the motor stalls, know the motor is at bottom.
MikeGray92 4:89ebfa37663b 43 while(stallcount < 3){wait(.01);}
MikeGray92 4:89ebfa37663b 44 liftSpeed.write(0);
MikeGray92 4:89ebfa37663b 45 currentPosition = 0;
MikeGray92 10:836e701d00a6 46 wait(0.1);
MikeGray92 10:836e701d00a6 47 liftDirection.write(LIFTUP);
MikeGray92 10:836e701d00a6 48 liftSpeed.write(0.3);
MikeGray92 10:836e701d00a6 49 wait(0.1);
MikeGray92 10:836e701d00a6 50 liftSpeed.write(0);
MikeGray92 4:89ebfa37663b 51 stopHallInt();
MikeGray92 10:836e701d00a6 52 rosInput.height = LIFTHEIGHTMIN;
MikeGray92 10:836e701d00a6 53 rosInput.heightSpeed = 0;
group-UVic-Assistive-Technolog 0:3a767f41cf04 54 }
group-UVic-Assistive-Technolog 0:3a767f41cf04 55
MikeGray92 7:950b3c3b5a2b 56 void setupROSNode(ros::NodeHandle& nh, ros::Subscriber<std_msgs::Int32MultiArray>& sub){
group-UVic-Assistive-Technolog 0:3a767f41cf04 57 nh.getHardware()->setBaud(57600);
group-UVic-Assistive-Technolog 0:3a767f41cf04 58 nh.initNode();
group-UVic-Assistive-Technolog 0:3a767f41cf04 59 nh.subscribe(sub);
group-UVic-Assistive-Technolog 0:3a767f41cf04 60 }
MikeGray92 4:89ebfa37663b 61
MikeGray92 6:2ffa254e8f6e 62 void startHallInt() { // Starting hall effect timer interrupt
MikeGray92 4:89ebfa37663b 63 hallInt.attach(&hallInterrupt, 0.03);
MikeGray92 4:89ebfa37663b 64 }
group-UVic-Assistive-Technolog 0:3a767f41cf04 65
MikeGray92 6:2ffa254e8f6e 66 void stopHallInt() { // Stopping hall effect timer interrupt
MikeGray92 4:89ebfa37663b 67 hallInt.detach();
MikeGray92 4:89ebfa37663b 68 }