Skip to content

Commit

Permalink
Exit if objective is done before timeout
Browse files Browse the repository at this point in the history
  • Loading branch information
mkhansenbot committed Oct 24, 2024
1 parent 3240211 commit 33e0200
Showing 1 changed file with 11 additions and 4 deletions.
15 changes: 11 additions & 4 deletions moveit_studio_py/examples/start_stop_async.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@
from moveit_msgs.msg import MoveItErrorCodes
from moveit_studio_py.objective_manager import ObjectiveManager

done = False

def done_cb(future: rclpy.task.Future) -> None:
"""
Expand All @@ -51,6 +52,8 @@ def done_cb(future: rclpy.task.Future) -> None:
print("Objective executed successfully!")
else:
print(f"MoveItErrorCode Value: {result.error_code.val}")
global done
done = True


def main():
Expand All @@ -74,14 +77,18 @@ def main():
objective_manager = ObjectiveManager()

print(f"Starting {args.objective_name}.")
global done
done = False
objective_manager.start_objective(
args.objective_name, blocking=False, async_callback=done_cb
)
cancel_time = time.time() + args.wait_time
while not done and time.time() < cancel_time:
time.sleep(1)

time.sleep(args.wait_time)

print(f"Stopping {args.objective_name}.")
objective_manager.stop_objective()
if not done:
print(f"Stopping {args.objective_name}.")
objective_manager.stop_objective()

rclpy.shutdown()

Expand Down

0 comments on commit 33e0200

Please sign in to comment.