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: lift.cpp
- Revision:
- 10:836e701d00a6
- Parent:
- 7:950b3c3b5a2b
- Child:
- 13:8630f38f8066
--- a/lift.cpp Mon Mar 26 21:32:30 2018 +0000 +++ b/lift.cpp Thu Apr 26 18:33:11 2018 +0000 @@ -1,4 +1,4 @@ - + #include <stdint.h> #include "mbed.h" #include <ros.h> @@ -15,12 +15,13 @@ void runLift(void){ stallCheck(); //Check If Arrived - if (abs(control.height - currentPosition) < 5){ + if (abs(control.height - currentPosition) < 6){ liftSpeed.write(0); stopHallInt(); startFlag = 0; } else { + value1.write(1); if(startFlag == 0){ startHallInt(); startFlag = 1; @@ -32,20 +33,20 @@ else if(control.height < currentPosition){ liftDirection.write(LIFTDOWN); } - liftSpeed.write(0.5); + liftSpeed.write(liftDutyCycle); } } //Determining if the lift stalled and stopping if it is void stallCheck(void){ - if(stallcount > 3 && liftSpeed.read() > 0){ + if(stallcount > 3 && liftSpeed.read() > 0 && eStopFlag == 0){ liftSpeed.write(0); if (liftDirection.read() == LIFTUP){ currentPosition = LIFTHEIGHTMAX; - control.height = currentPosition; + control.height = LIFTHEIGHTMAX; }else{ currentPosition = 0; - control.height = currentPosition; + control.height = 0; } } } \ No newline at end of file