UVic Assistive Technology Lab / Mbed 2 deprecated DSLR_Camera_Gimbal

Dependencies:   mbed ros_lib_kinetic

Committer:
MikeGray92
Date:
Fri Dec 14 03:28:55 2018 +0000
Revision:
13:8630f38f8066
Parent:
10:836e701d00a6
2019 demo code

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