diff --git a/test_communication/test/action_server_py.py b/test_communication/test/action_server_py.py index c6b95f33..9ee2c932 100644 --- a/test_communication/test/action_server_py.py +++ b/test_communication/test/action_server_py.py @@ -38,7 +38,7 @@ def execute_callback(goal_handle): return expected_goal.execute_goal(goal_handle) # Not an expected goal (this should not happen) print('Unexpected goal received by action server', file=sys.stderr) - goal_handle.set_aborted() + goal_handle.abort() return action_type.Result() action_name = 'test/action/' + action_type.__name__ @@ -61,12 +61,12 @@ def execute_goal(goal_handle): for i in range(1, goal.order): if not rclpy.ok(): - goal_handle.set_aborted() + goal_handle.abort() return Fibonacci.Result() # Check if the goal was canceled if goal_handle.is_cancel_requested: - goal_handle.set_canceled() + goal_handle.cancel() result = Fibonacci.Result() result.sequence = feedback.sequence print('Goal was canceled') @@ -85,7 +85,7 @@ def execute_goal(goal_handle): # Send final result result = Fibonacci.Result() result.sequence = feedback.sequence - goal_handle.set_succeeded() + goal_handle.succeed() print('Goal succeeded') return result @@ -118,12 +118,12 @@ def execute_goal(goal_handle): num_feedback = 10 for i in range(0, num_feedback): if not rclpy.ok(): - goal_handle.set_aborted() + goal_handle.abort() return NestedMessage.Result() # Check if the goal was canceled if goal_handle.is_cancel_requested: - goal_handle.set_canceled() + goal_handle.cancel() print('Goal was canceled') return result @@ -135,7 +135,7 @@ def execute_goal(goal_handle): time.sleep(0.1) # Send final result - goal_handle.set_succeeded() + goal_handle.succeed() print('Goal succeeded') return result diff --git a/test_communication/test/test_action_server.cpp b/test_communication/test/test_action_server.cpp index ddddda6c..c0df4208 100644 --- a/test_communication/test/test_action_server.cpp +++ b/test_communication/test/test_action_server.cpp @@ -142,7 +142,7 @@ generate_expected_fibonacci_goals(rclcpp::Logger logger) // Check if the goal was canceled. if (goal_handle->is_canceling()) { result->sequence = feedback->sequence; - goal_handle->set_canceled(result); + goal_handle->cancel(result); RCLCPP_INFO(logger, "goal was canceled"); return; } @@ -157,7 +157,7 @@ generate_expected_fibonacci_goals(rclcpp::Logger logger) } result->sequence = feedback->sequence; - goal_handle->set_succeeded(result); + goal_handle->succeed(result); RCLCPP_INFO(logger, "goal succeeded"); }; @@ -213,7 +213,7 @@ generate_expected_nested_message_goals(rclcpp::Logger logger) // Check if the goal was canceled. if (goal_handle->is_canceling()) { result->nested_field.int32_value = result_value; - goal_handle->set_canceled(result); + goal_handle->cancel(result); RCLCPP_INFO(logger, "goal was canceled"); return; } @@ -227,7 +227,7 @@ generate_expected_nested_message_goals(rclcpp::Logger logger) } result->nested_field.int32_value = result_value; - goal_handle->set_succeeded(result); + goal_handle->succeed(result); RCLCPP_INFO(logger, "goal succeeded"); };