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
Diff: initializations.cpp
- Revision:
- 10:836e701d00a6
- Parent:
- 7:950b3c3b5a2b
- Child:
- 13:8630f38f8066
--- a/initializations.cpp Mon Mar 26 21:32:30 2018 +0000 +++ b/initializations.cpp Thu Apr 26 18:33:11 2018 +0000 @@ -12,12 +12,21 @@ // Set the Gimbal at the zero position. gimbal.servo(YAWID, YAWZERO, 50); control.yaw = YAWZERO; + control.yawSpeed = 50; + rosInput.yaw = YAWZERO; + rosInput.yawSpeed = 50; wait(0.1); gimbal.servo(PITCHID, PITCHZERO, 50); control.pitch = PITCHZERO; + control.pitchSpeed = 50; + rosInput.pitch = PITCHZERO; + rosInput.pitchSpeed = 50; wait(0.1); gimbal.servo(ROLLID, ROLLZERO, 50); control.roll = ROLLZERO; + control.rollSpeed = 50; + rosInput.roll = ROLLZERO; + rosInput.rollSpeed = 50; } void setupLift(){ @@ -29,11 +38,19 @@ liftDirection.write(LIFTDOWN); liftSpeed.write(0.3); + // Wait until the motor stalls, know the motor is at bottom. while(stallcount < 3){wait(.01);} liftSpeed.write(0); currentPosition = 0; + wait(0.1); + liftDirection.write(LIFTUP); + liftSpeed.write(0.3); + wait(0.1); + liftSpeed.write(0); stopHallInt(); + rosInput.height = LIFTHEIGHTMIN; + rosInput.heightSpeed = 0; } void setupROSNode(ros::NodeHandle& nh, ros::Subscriber<std_msgs::Int32MultiArray>& sub){