Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: mbed ros_lib_kinetic
initializations.cpp
- Committer:
- MikeGray92
- Date:
- 2018-02-08
- Revision:
- 3:527f0b949839
- Parent:
- 2:0537a8007a39
- Child:
- 4:89ebfa37663b
File content as of revision 3:527f0b949839:
#include <std_msgs/Empty.h> #include <std_msgs/Float32MultiArray.h> #include <initializations.h> #include <ros.h> #include <definitions.h> #include <prototypes.h> #include "mbed.h" // Initializations void setupGimbal(){ gimbal.servo(YAWID, YAWZERO, 50); // Set the Gimbal at the zero position. control.yaw = YAWZERO; wait(0.1); gimbal.servo(PITCHID, PITCHZERO, 50); control.pitch = PITCHZERO; wait(0.1); gimbal.servo(ROLLID, ROLLZERO, 50); control.roll = ROLLZERO; } void setupLift(){ hallInt.attach(&hallInterrupt, 0.05); liftSpeed.period_us(50); // Find the bottom position. Go down at lowest speed and set zero point. liftDirection.write(LIFTDOWN); liftSpeed.write(0.3); // Wait until the motor stalls, know the motor is at bottom. while(!stall){wait(.01);} if(stall == true){ liftSpeed.write(0); currentPosition = 0; stall = false; } } void setupROSNode(ros::NodeHandle& nh, ros::Subscriber<std_msgs::Float32MultiArray>& sub){ nh.getHardware()->setBaud(57600); nh.initNode(); nh.subscribe(sub); }