|
21 | 21 |
|
22 | 22 | import rclpy |
23 | 23 | from rclpy.action import ActionServer, CancelResponse, GoalResponse |
| 24 | +from rclpy.action.server import ServerGoalHandle |
24 | 25 | from rclpy.callback_groups import ReentrantCallbackGroup |
25 | 26 | from rclpy.executors import MultiThreadedExecutor, SingleThreadedExecutor |
26 | 27 |
|
@@ -419,7 +420,7 @@ def execute_callback(gh): |
419 | 420 | # Execute the goal |
420 | 421 | server_goal_handle.execute() |
421 | 422 |
|
422 | | - # Get the result and exepect it to have canceled status |
| 423 | + # Get the result and expect it to have canceled status |
423 | 424 | get_result_future = self.mock_action_client.get_result(goal_uuid) |
424 | 425 | rclpy.spin_until_future_complete(self.node, get_result_future, self.executor) |
425 | 426 | result = get_result_future.result() |
@@ -684,6 +685,53 @@ def execute_with_feedback(goal_handle): |
684 | 685 | finally: |
685 | 686 | action_server.destroy() |
686 | 687 |
|
| 688 | + def test_without_execute_cb(self): |
| 689 | + # Just like test_execute_succeed, but without an execute callback |
| 690 | + # Goal handle is stored and succeeded from outside the execute callback |
| 691 | + stored_goal_handle = None |
| 692 | + |
| 693 | + def handle_accepted_callback(goal_handle: ServerGoalHandle): |
| 694 | + goal_handle.executing() |
| 695 | + nonlocal stored_goal_handle |
| 696 | + stored_goal_handle = goal_handle |
| 697 | + |
| 698 | + executor = MultiThreadedExecutor(context=self.context) |
| 699 | + |
| 700 | + action_server = ActionServer( |
| 701 | + self.node, |
| 702 | + Fibonacci, |
| 703 | + 'fibonacci', |
| 704 | + handle_accepted_callback=handle_accepted_callback, |
| 705 | + ) |
| 706 | + |
| 707 | + goal_uuid = UUID(uuid=list(uuid.uuid4().bytes)) |
| 708 | + goal_msg = Fibonacci.Impl.SendGoalService.Request() |
| 709 | + goal_msg.goal_id = goal_uuid |
| 710 | + goal_future = self.mock_action_client.send_goal(goal_msg) |
| 711 | + rclpy.spin_until_future_complete(self.node, goal_future, executor) |
| 712 | + goal_handle = goal_future.result() |
| 713 | + self.assertTrue(goal_handle.accepted) |
| 714 | + |
| 715 | + get_result_future = self.mock_action_client.get_result(goal_uuid) |
| 716 | + self.assertFalse(get_result_future.done()) |
| 717 | + |
| 718 | + result = Fibonacci.Result() |
| 719 | + result.sequence.extend([1, 1, 2, 3, 5]) |
| 720 | + stored_goal_handle.succeed(result) |
| 721 | + |
| 722 | + # Handle all callbacks |
| 723 | + for _ in range(5): |
| 724 | + rclpy.spin_once(self.node, executor=self.executor, timeout_sec=0.01) |
| 725 | + if get_result_future.done(): |
| 726 | + break |
| 727 | + self.assertTrue(get_result_future.done()) |
| 728 | + |
| 729 | + result_response = get_result_future.result() |
| 730 | + |
| 731 | + self.assertEqual(result_response.status, GoalStatus.STATUS_SUCCEEDED) |
| 732 | + self.assertEqual(result_response.result.sequence.tolist(), [1, 1, 2, 3, 5]) |
| 733 | + action_server.destroy() |
| 734 | + |
687 | 735 |
|
688 | 736 | if __name__ == '__main__': |
689 | 737 | unittest.main() |
0 commit comments