-
Notifications
You must be signed in to change notification settings - Fork 499
Add preempted ResultCode for WrappedResult and preempt API for ServerGoalHandle #1117
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
base: rolling
Are you sure you want to change the base?
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -37,7 +37,8 @@ enum class ResultCode : int8_t | |
| UNKNOWN = action_msgs::msg::GoalStatus::STATUS_UNKNOWN, | ||
| SUCCEEDED = action_msgs::msg::GoalStatus::STATUS_SUCCEEDED, | ||
| CANCELED = action_msgs::msg::GoalStatus::STATUS_CANCELED, | ||
| ABORTED = action_msgs::msg::GoalStatus::STATUS_ABORTED | ||
| ABORTED = action_msgs::msg::GoalStatus::STATUS_ABORTED, | ||
| PREEMPTED = 7 // action_msgs::msg::GoalStatus::STATUS_PREEMPTED | ||
|
Collaborator
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Yeah, please add this to the GoalStatus |
||
| }; | ||
|
|
||
|
|
||
|
|
@@ -65,7 +66,7 @@ class ClientGoalHandle | |
| { | ||
| /// The unique identifier of the goal | ||
| GoalUUID goal_id; | ||
| /// A status to indicate if the goal was canceled, aborted, or suceeded | ||
| /// A status to indicate if the goal was canceled, aborted, preempted, or succeeded | ||
| ResultCode code; | ||
| /// User defined fields sent back with an action | ||
| typename ActionT::Result::SharedPtr result; | ||
|
|
||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -662,6 +662,80 @@ TEST_F(TestServer, publish_status_aborted) | |
| EXPECT_EQ(uuid, msg->status_list.at(0).goal_info.goal_id.uuid); | ||
| } | ||
|
|
||
| TEST_F(TestServer, publish_status_preemped) | ||
| { | ||
| auto node = std::make_shared<rclcpp::Node>("status_preempted", "/rclcpp_action/status_preempted"); | ||
| const GoalUUID uuid{{1, 2, 3, 40, 5, 6, 70, 8, 9, 1, 11, 120, 13, 140, 15, 160}}; | ||
|
|
||
| auto handle_goal = []( | ||
| const GoalUUID &, std::shared_ptr<const Fibonacci::Goal>) | ||
| { | ||
| return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; | ||
| }; | ||
|
|
||
| using GoalHandle = rclcpp_action::ServerGoalHandle<Fibonacci>; | ||
|
|
||
| auto handle_cancel = [](std::shared_ptr<GoalHandle>) | ||
| { | ||
| return rclcpp_action::CancelResponse::REJECT; | ||
| }; | ||
|
|
||
| std::shared_ptr<GoalHandle> received_handle; | ||
| auto handle_accepted = [&received_handle](std::shared_ptr<GoalHandle> handle) | ||
| { | ||
| received_handle = handle; | ||
| }; | ||
|
|
||
| auto as = rclcpp_action::create_server<Fibonacci>( | ||
| node, "fibonacci", | ||
| handle_goal, | ||
| handle_cancel, | ||
| handle_accepted); | ||
| (void)as; | ||
|
|
||
| // Subscribe to status messages | ||
| std::vector<action_msgs::msg::GoalStatusArray::SharedPtr> received_msgs; | ||
| auto subscriber = node->create_subscription<action_msgs::msg::GoalStatusArray>( | ||
| "fibonacci/_action/status", 10, | ||
| [&received_msgs](action_msgs::msg::GoalStatusArray::SharedPtr list) | ||
| { | ||
| received_msgs.push_back(list); | ||
| }); | ||
|
|
||
| send_goal_request(node, uuid); | ||
|
|
||
| // Send result request | ||
| auto result_client = node->create_client<Fibonacci::Impl::GetResultService>( | ||
| "fibonacci/_action/get_result"); | ||
| if (!result_client->wait_for_service(std::chrono::seconds(20))) { | ||
| throw std::runtime_error("get result service didn't become available"); | ||
| } | ||
| auto request = std::make_shared<Fibonacci::Impl::GetResultService::Request>(); | ||
| request->goal_id.uuid = uuid; | ||
| auto future = result_client->async_send_request(request); | ||
|
|
||
| // Send a result | ||
| auto result = std::make_shared<Fibonacci::Result>(); | ||
| result->sequence = {5, 8, 13, 21}; | ||
| received_handle->preempt(result); | ||
|
|
||
| // Wait for the result request to be received | ||
| ASSERT_EQ( | ||
| rclcpp::FutureReturnCode::SUCCESS, | ||
| rclcpp::spin_until_future_complete(node, future)); | ||
|
|
||
| auto response = future.get(); | ||
| // EXPECT_EQ(action_msgs::msg::GoalStatus::STATUS_PREEMPTED, response->status); | ||
| EXPECT_EQ(7, response->status); | ||
| EXPECT_EQ(result->sequence, response->result.sequence); | ||
|
|
||
| ASSERT_LT(0u, received_msgs.size()); | ||
| auto & msg = received_msgs.back(); | ||
| ASSERT_EQ(1u, msg->status_list.size()); | ||
| EXPECT_EQ(action_msgs::msg::GoalStatus::STATUS_ABORTED, msg->status_list.at(0).status); | ||
|
Collaborator
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. This is expected to STATUS_ABORTED? not STATUS_PREEMPTED?
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. The
Collaborator
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. thanks, i understand now. |
||
| EXPECT_EQ(uuid, msg->status_list.at(0).goal_info.goal_id.uuid); | ||
| } | ||
|
|
||
| TEST_F(TestServer, publish_feedback) | ||
| { | ||
| auto node = std::make_shared<rclcpp::Node>("pub_feedback", "/rclcpp_action/pub_feedback"); | ||
|
|
||
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
https://github.com/ros2/rcl_interfaces/blob/master/action_msgs/msg/GoalStatus.msg needs to be updated.