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:
- 4:89ebfa37663b
- Parent:
- 3:527f0b949839
- Child:
- 6:2ffa254e8f6e
--- a/initializations.cpp Thu Feb 08 22:55:15 2018 +0000 +++ b/initializations.cpp Mon Mar 05 23:08:34 2018 +0000 @@ -21,7 +21,7 @@ void setupLift(){ - hallInt.attach(&hallInterrupt, 0.05); + startHallInt(); liftSpeed.period_us(50); // Find the bottom position. Go down at lowest speed and set zero point. @@ -29,13 +29,15 @@ 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; - } - + while(stallcount < 3){wait(.01);} + liftSpeed.write(0); + currentPosition = 0; + stopHallInt(); + wait(0.1); + liftDirection.write(LIFTUP); + liftSpeed.write(0.3); + wait(0.1); + liftSpeed.write(0); } void setupROSNode(ros::NodeHandle& nh, ros::Subscriber<std_msgs::Float32MultiArray>& sub){ @@ -44,5 +46,12 @@ nh.initNode(); nh.subscribe(sub); } - + +void startHallInt() { + hallInt.attach(&hallInterrupt, 0.03); +} +void stopHallInt() { + hallInt.detach(); +} +