From e813b712997634e65a1f1a4861f920b9e98fdd32 Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Tue, 12 Feb 2019 12:15:35 -0800 Subject: [PATCH 01/10] match renamed action types --- .../include/rclcpp_action/client.hpp | 59 +++++++++---------- .../rclcpp_action/client_goal_handle.hpp | 3 +- .../include/rclcpp_action/server.hpp | 22 +++---- .../rclcpp_action/server_goal_handle.hpp | 24 ++++---- rclcpp_action/test/test_client.cpp | 54 ++++++++--------- rclcpp_action/test/test_server.cpp | 47 ++++++++------- 6 files changed, 101 insertions(+), 108 deletions(-) diff --git a/rclcpp_action/include/rclcpp_action/client.hpp b/rclcpp_action/include/rclcpp_action/client.hpp index 0ce4b4a948..79273542ac 100644 --- a/rclcpp_action/include/rclcpp_action/client.hpp +++ b/rclcpp_action/include/rclcpp_action/client.hpp @@ -262,8 +262,8 @@ class Client : public ClientBase using GoalHandle = ClientGoalHandle; using Result = typename GoalHandle::Result; using FeedbackCallback = typename ClientGoalHandle::FeedbackCallback; - using CancelRequest = typename ActionT::CancelGoalService::Request; - using CancelResponse = typename ActionT::CancelGoalService::Response; + using CancelRequest = typename ActionT::Impl::CancelGoalService::Request; + using CancelResponse = typename ActionT::Impl::CancelGoalService::Response; Client( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base, @@ -286,18 +286,16 @@ class Client : public ClientBase // Put promise in the heap to move it around. auto promise = std::make_shared>(); std::shared_future future(promise->get_future()); - using GoalRequest = typename ActionT::GoalRequestService::Request; - // auto goal_request = std::make_shared(); - // goal_request->goal_id = this->generate_goal_id(); - // goal_request->goal = goal; - auto goal_request = std::make_shared(goal); - goal_request->action_goal_id.uuid = this->generate_goal_id(); + using GoalRequest = typename ActionT::Impl::SendGoalService::Request; + auto goal_request = std::make_shared(); + goal_request->goal_id = this->generate_goal_id(); + goal_request->goal = goal; this->send_goal_request( std::static_pointer_cast(goal_request), [this, goal_request, callback, ignore_result, promise]( std::shared_ptr response) mutable { - using GoalResponse = typename ActionT::GoalRequestService::Response; + using GoalResponse = typename ActionT::Impl::SendGoalService::Response; auto goal_response = std::static_pointer_cast(response); if (!goal_response->accepted) { promise->set_value(nullptr); @@ -305,7 +303,7 @@ class Client : public ClientBase } GoalInfo goal_info; // goal_info.goal_id = goal_request->goal_id; - goal_info.goal_id.uuid = goal_request->action_goal_id.uuid; + goal_info.goal_id.uuid = goal_request->goal_id; goal_info.stamp = goal_response->stamp; // Do not use std::make_shared as friendship cannot be forwarded. std::shared_ptr goal_handle(new GoalHandle(goal_info, callback)); @@ -406,7 +404,7 @@ class Client : public ClientBase std::shared_ptr create_goal_response() const override { - using GoalResponse = typename ActionT::GoalRequestService::Response; + using GoalResponse = typename ActionT::Impl::SendGoalService::Response; return std::shared_ptr(new GoalResponse()); } @@ -414,7 +412,7 @@ class Client : public ClientBase std::shared_ptr create_result_response() const override { - using GoalResultResponse = typename ActionT::GoalResultService::Response; + using GoalResultResponse = typename ActionT::Impl::GetResultService::Response; return std::shared_ptr(new GoalResultResponse()); } @@ -429,9 +427,8 @@ class Client : public ClientBase std::shared_ptr create_feedback_message() const override { - // using FeedbackMessage = typename ActionT::FeedbackMessage; - // return std::shared_ptr(new FeedbackMessage()); - return std::shared_ptr(new Feedback()); + using FeedbackMessage = typename ActionT::Impl::FeedbackMessage; + return std::shared_ptr(new FeedbackMessage()); } /// \internal @@ -439,13 +436,10 @@ class Client : public ClientBase handle_feedback_message(std::shared_ptr message) override { std::lock_guard guard(goal_handles_mutex_); - // using FeedbackMessage = typename ActionT::FeedbackMessage; - // typename FeedbackMessage::SharedPtr feedback_message = - // std::static_pointer_cast(message); - typename Feedback::SharedPtr feedback_message = - std::static_pointer_cast(message); - // const GoalID & goal_id = feedback_message->goal_id; - const GoalID & goal_id = feedback_message->action_goal_id.uuid; + using FeedbackMessage = typename ActionT::Impl::FeedbackMessage; + typename FeedbackMessage::SharedPtr feedback_message = + std::static_pointer_cast(message); + const GoalID & goal_id = feedback_message->goal_id; if (goal_handles_.count(goal_id) == 0) { RCLCPP_DEBUG( this->get_logger(), @@ -453,15 +447,16 @@ class Client : public ClientBase return; } typename GoalHandle::SharedPtr goal_handle = goal_handles_[goal_id]; - // goal_handle->call_feedback_callback(goal_handle, feedback_message->feedback); - goal_handle->call_feedback_callback(goal_handle, feedback_message); + auto feedback = std::make_shared(); + *feedback = feedback_message->feedback; + goal_handle->call_feedback_callback(goal_handle, feedback); } /// \internal std::shared_ptr create_status_message() const override { - using GoalStatusMessage = typename ActionT::GoalStatusMessage; + using GoalStatusMessage = typename ActionT::Impl::GoalStatusMessage; return std::shared_ptr(new GoalStatusMessage()); } @@ -470,7 +465,7 @@ class Client : public ClientBase handle_status_message(std::shared_ptr message) override { std::lock_guard guard(goal_handles_mutex_); - using GoalStatusMessage = typename ActionT::GoalStatusMessage; + using GoalStatusMessage = typename ActionT::Impl::GoalStatusMessage; auto status_message = std::static_pointer_cast(message); for (const GoalStatus & status : status_message->status_list) { // const GoalID & goal_id = status.goal_info.goal_id; @@ -498,20 +493,22 @@ class Client : public ClientBase void make_result_aware(typename GoalHandle::SharedPtr goal_handle) { - using GoalResultRequest = typename ActionT::GoalResultService::Request; + using GoalResultRequest = typename ActionT::Impl::GetResultService::Request; auto goal_result_request = std::make_shared(); // goal_result_request.goal_id = goal_handle->get_goal_id(); - goal_result_request->action_goal_id.uuid = goal_handle->get_goal_id(); + goal_result_request->goal_id = goal_handle->get_goal_id(); this->send_result_request( std::static_pointer_cast(goal_result_request), [goal_handle, this](std::shared_ptr response) mutable { // Wrap the response in a struct with the fields a user cares about Result result; - using GoalResultResponse = typename ActionT::GoalResultService::Response; - result.response = std::static_pointer_cast(response); + using GoalResultResponse = typename ActionT::Impl::GetResultService::Response; + auto result_response = std::static_pointer_cast(response); + result.response = std::make_shared(); + *result.response = result_response->result; result.goal_id = goal_handle->get_goal_id(); - result.code = static_cast(result.response->action_status); + result.code = static_cast(result_response->status); goal_handle->set_result(result); std::lock_guard lock(goal_handles_mutex_); goal_handles_.erase(goal_handle->get_goal_id()); diff --git a/rclcpp_action/include/rclcpp_action/client_goal_handle.hpp b/rclcpp_action/include/rclcpp_action/client_goal_handle.hpp index 03ae985861..8fb629c87f 100644 --- a/rclcpp_action/include/rclcpp_action/client_goal_handle.hpp +++ b/rclcpp_action/include/rclcpp_action/client_goal_handle.hpp @@ -65,7 +65,8 @@ class ClientGoalHandle using Feedback = typename ActionT::Feedback; using FeedbackCallback = std::function::SharedPtr, const std::shared_ptr)>; + typename ClientGoalHandle::SharedPtr, + const std::shared_ptr)>; virtual ~ClientGoalHandle(); diff --git a/rclcpp_action/include/rclcpp_action/server.hpp b/rclcpp_action/include/rclcpp_action/server.hpp index b1bb47a4f8..8288f6a090 100644 --- a/rclcpp_action/include/rclcpp_action/server.hpp +++ b/rclcpp_action/include/rclcpp_action/server.hpp @@ -337,14 +337,10 @@ class Server : public ServerBase, public std::enable_shared_from_this> call_handle_goal_callback(GoalID & uuid, std::shared_ptr message) override { - // TODO(sloretz) update and remove assert when IDL pipeline allows nesting user's type - static_assert( - std::is_same::value, - "Assuming user fields were merged with goal request fields"); GoalResponse user_response = handle_goal_( uuid, std::static_pointer_cast(message)); - auto ros_response = std::make_shared(); + auto ros_response = std::make_shared(); ros_response->accepted = GoalResponse::ACCEPT_AND_EXECUTE == user_response || GoalResponse::ACCEPT_AND_DEFER == user_response; return std::make_pair(user_response, ros_response); @@ -408,8 +404,8 @@ class Server : public ServerBase, public std::enable_shared_from_thispublish_status(); }; - std::function)> publish_feedback = - [weak_this](std::shared_ptr feedback_msg) + std::function)> publish_feedback = + [weak_this](std::shared_ptr feedback_msg) { std::shared_ptr> shared_this = weak_this.lock(); if (!shared_this) { @@ -435,14 +431,14 @@ class Server : public ServerBase, public std::enable_shared_from_this(message)->action_goal_id.uuid; + static_cast(message)->goal_id; } /// \internal std::shared_ptr create_goal_request() override { - return std::shared_ptr(new typename ActionT::GoalRequestService::Request()); + return std::shared_ptr(new typename ActionT::Impl::SendGoalService::Request()); } /// \internal @@ -450,22 +446,22 @@ class Server : public ServerBase, public std::enable_shared_from_this(message)->action_goal_id.uuid; + static_cast(message)->goal_id; } /// \internal std::shared_ptr create_result_request() override { - return std::shared_ptr(new typename ActionT::GoalResultService::Request()); + return std::shared_ptr(new typename ActionT::Impl::GetResultService::Request()); } /// \internal std::shared_ptr create_result_response(decltype(action_msgs::msg::GoalStatus::status) status) override { - auto result = std::make_shared(); - result->action_status = status; + auto result = std::make_shared(); + result->status = status; return std::static_pointer_cast(result); } diff --git a/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp b/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp index 5b06fc6059..00aecdd718 100644 --- a/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp +++ b/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp @@ -145,9 +145,9 @@ class ServerGoalHandle : public ServerGoalHandleBase * \param[in] feedback_msg the message to publish to clients. */ void - publish_feedback(std::shared_ptr feedback_msg) + publish_feedback(std::shared_ptr feedback_msg) { - feedback_msg->action_goal_id.uuid = uuid_; + feedback_msg->goal_id = uuid_; publish_feedback_(feedback_msg); } @@ -162,10 +162,10 @@ class ServerGoalHandle : public ServerGoalHandleBase * \param[in] result_msg the final result to send to clients. */ void - set_aborted(typename ActionT::Result::SharedPtr result_msg) + set_aborted(typename ActionT::Impl::GetResultService::Response::SharedPtr result_msg) { _set_aborted(); - result_msg->action_status = action_msgs::msg::GoalStatus::STATUS_ABORTED; + result_msg->status = action_msgs::msg::GoalStatus::STATUS_ABORTED; on_terminal_state_(uuid_, result_msg); } @@ -179,10 +179,10 @@ class ServerGoalHandle : public ServerGoalHandleBase * \param[in] result_msg the final result to send to clients. */ void - set_succeeded(typename ActionT::Result::SharedPtr result_msg) + set_succeeded(typename ActionT::Impl::GetResultService::Response::SharedPtr result_msg) { _set_succeeded(); - result_msg->action_status = action_msgs::msg::GoalStatus::STATUS_SUCCEEDED; + result_msg->status = action_msgs::msg::GoalStatus::STATUS_SUCCEEDED; on_terminal_state_(uuid_, result_msg); } @@ -196,10 +196,10 @@ class ServerGoalHandle : public ServerGoalHandleBase * \param[in] result_msg the final result to send to clients. */ void - set_canceled(typename ActionT::Result::SharedPtr result_msg) + set_canceled(typename ActionT::Impl::GetResultService::Response::SharedPtr result_msg) { _set_canceled(); - result_msg->action_status = action_msgs::msg::GoalStatus::STATUS_CANCELED; + result_msg->status = action_msgs::msg::GoalStatus::STATUS_CANCELED; on_terminal_state_(uuid_, result_msg); } @@ -233,8 +233,8 @@ class ServerGoalHandle : public ServerGoalHandleBase { // Cancel goal if handle was allowed to destruct without reaching a terminal state if (try_canceling()) { - auto null_result = std::make_shared(); - null_result->action_status = action_msgs::msg::GoalStatus::STATUS_CANCELED; + auto null_result = std::make_shared(); + null_result->status = action_msgs::msg::GoalStatus::STATUS_CANCELED; on_terminal_state_(uuid_, null_result); } } @@ -247,7 +247,7 @@ class ServerGoalHandle : public ServerGoalHandleBase std::shared_ptr goal, std::function)> on_terminal_state, std::function on_executing, - std::function)> publish_feedback + std::function)> publish_feedback ) : ServerGoalHandleBase(rcl_handle), goal_(goal), uuid_(uuid), on_terminal_state_(on_terminal_state), on_executing_(on_executing), @@ -265,7 +265,7 @@ class ServerGoalHandle : public ServerGoalHandleBase std::function)> on_terminal_state_; std::function on_executing_; - std::function)> publish_feedback_; + std::function)> publish_feedback_; }; } // namespace rclcpp_action diff --git a/rclcpp_action/test/test_client.cpp b/rclcpp_action/test/test_client.cpp index ee17a4a884..422b9d9d84 100644 --- a/rclcpp_action/test/test_client.cpp +++ b/rclcpp_action/test/test_client.cpp @@ -24,7 +24,6 @@ #include #include #include -#include #include #include #include @@ -55,17 +54,17 @@ class TestClient : public ::testing::Test using ActionType = test_msgs::action::Fibonacci; using ActionGoal = ActionType::Goal; using ActionGoalHandle = rclcpp_action::ClientGoalHandle; - using ActionGoalRequestService = ActionType::GoalRequestService; + using ActionGoalRequestService = ActionType::Impl::SendGoalService; using ActionGoalRequest = ActionGoalRequestService::Request; using ActionGoalResponse = ActionGoalRequestService::Response; - using ActionGoalResultService = ActionType::GoalResultService; + using ActionGoalResultService = ActionType::Impl::GetResultService; using ActionGoalResultRequest = ActionGoalResultService::Request; using ActionGoalResultResponse = ActionGoalResultService::Response; - using ActionCancelGoalService = ActionType::CancelGoalService; - using ActionCancelGoalRequest = ActionType::CancelGoalService::Request; - using ActionCancelGoalResponse = ActionType::CancelGoalService::Response; - using ActionStatusMessage = ActionType::GoalStatusMessage; - using ActionFeedbackMessage = ActionType::Feedback; + using ActionCancelGoalService = ActionType::Impl::CancelGoalService; + using ActionCancelGoalRequest = ActionType::Impl::CancelGoalService::Request; + using ActionCancelGoalResponse = ActionType::Impl::CancelGoalService::Response; + using ActionStatusMessage = ActionType::Impl::GoalStatusMessage; + using ActionFeedbackMessage = ActionType::Impl::FeedbackMessage; using ActionFeedback = ActionType::Feedback; static void SetUpTestCase() @@ -90,9 +89,9 @@ class TestClient : public ::testing::Test ActionGoalResponse::SharedPtr response) { response->stamp = clock.now(); - response->accepted = (request->order >= 0); + response->accepted = (request->goal.order >= 0); if (response->accepted) { - goals[request->action_goal_id.uuid] = {request, response}; + goals[request->goal_id] = {request, response}; } }); ASSERT_TRUE(goal_service != nullptr); @@ -108,29 +107,30 @@ class TestClient : public ::testing::Test const ActionGoalResultRequest::SharedPtr request, ActionGoalResultResponse::SharedPtr response) { - if (goals.count(request->action_goal_id.uuid) == 1) { - auto goal_request = goals[request->action_goal_id.uuid].first; - auto goal_response = goals[request->action_goal_id.uuid].second; + if (goals.count(request->goal_id) == 1) { + auto goal_request = goals[request->goal_id].first; + auto goal_response = goals[request->goal_id].second; ActionStatusMessage status_message; rclcpp_action::GoalStatus goal_status; - goal_status.goal_info.goal_id.uuid = goal_request->action_goal_id.uuid; + goal_status.goal_info.goal_id.uuid = goal_request->goal_id; goal_status.goal_info.stamp = goal_response->stamp; goal_status.status = rclcpp_action::GoalStatus::STATUS_EXECUTING; status_message.status_list.push_back(goal_status); status_publisher->publish(status_message); client_executor.spin_once(); ActionFeedbackMessage feedback_message; - feedback_message.action_goal_id.uuid = goal_request->action_goal_id.uuid; - feedback_message.sequence.push_back(0); + feedback_message.goal_id = goal_request->goal_id; + feedback_message.feedback.sequence.push_back(0); feedback_publisher->publish(feedback_message); client_executor.spin_once(); - if (goal_request->order > 0) { - feedback_message.sequence.push_back(1); + if (goal_request->goal.order > 0) { + feedback_message.feedback.sequence.push_back(1); feedback_publisher->publish(feedback_message); client_executor.spin_once(); - for (int i = 1; i < goal_request->order; ++i) { - feedback_message.sequence.push_back( - feedback_message.sequence[i] + feedback_message.sequence[i - 1]); + for (int i = 1; i < goal_request->goal.order; ++i) { + feedback_message.feedback.sequence.push_back( + feedback_message.feedback.sequence[i] + + feedback_message.feedback.sequence[i - 1]); feedback_publisher->publish(feedback_message); client_executor.spin_once(); } @@ -139,11 +139,11 @@ class TestClient : public ::testing::Test status_message.status_list[0] = goal_status; status_publisher->publish(status_message); client_executor.spin_once(); - response->sequence = feedback_message.sequence; - response->action_status = rclcpp_action::GoalStatus::STATUS_SUCCEEDED; - goals.erase(request->action_goal_id.uuid); + response->result.sequence = feedback_message.feedback.sequence; + response->status = rclcpp_action::GoalStatus::STATUS_SUCCEEDED; + goals.erase(request->goal_id); } else { - response->action_status = rclcpp_action::GoalStatus::STATUS_UNKNOWN; + response->status = rclcpp_action::GoalStatus::STATUS_UNKNOWN; } }); ASSERT_TRUE(result_service != nullptr); @@ -172,11 +172,11 @@ class TestClient : public ::testing::Test auto goal_response = it->second.second; const rclcpp::Time goal_stamp = goal_response->stamp; bool cancel_this = ( - request->goal_info.goal_id.uuid == goal_request->action_goal_id.uuid || + request->goal_info.goal_id.uuid == goal_request->goal_id || cancel_stamp > goal_stamp); if (cancel_all || cancel_this) { rclcpp_action::GoalStatus goal_status; - goal_status.goal_info.goal_id.uuid = goal_request->action_goal_id.uuid; + goal_status.goal_info.goal_id.uuid = goal_request->goal_id; goal_status.goal_info.stamp = goal_response->stamp; goal_status.status = rclcpp_action::GoalStatus::STATUS_CANCELED; status_message.status_list.push_back(goal_status); diff --git a/rclcpp_action/test/test_server.cpp b/rclcpp_action/test/test_server.cpp index c46fd614cb..23c3a49a0d 100644 --- a/rclcpp_action/test/test_server.cpp +++ b/rclcpp_action/test/test_server.cpp @@ -36,16 +36,16 @@ class TestServer : public ::testing::Test rclcpp::init(0, nullptr); } - std::shared_ptr + std::shared_ptr send_goal_request(rclcpp::Node::SharedPtr node, GoalID uuid) { - auto client = node->create_client( + auto client = node->create_client( "fibonacci/_action/send_goal"); if (!client->wait_for_service(std::chrono::seconds(20))) { throw std::runtime_error("send goal service didn't become available"); } - auto request = std::make_shared(); - request->action_goal_id.uuid = uuid; + auto request = std::make_shared(); + request->goal_id = uuid; auto future = client->async_send_request(request); if (rclcpp::executor::FutureReturnCode::SUCCESS != rclcpp::spin_until_future_complete(node, future)) @@ -58,12 +58,12 @@ class TestServer : public ::testing::Test void send_cancel_request(rclcpp::Node::SharedPtr node, GoalID uuid) { - auto cancel_client = node->create_client( + auto cancel_client = node->create_client( "fibonacci/_action/cancel_goal"); if (!cancel_client->wait_for_service(std::chrono::seconds(20))) { throw std::runtime_error("cancel goal service didn't become available"); } - auto request = std::make_shared(); + auto request = std::make_shared(); request->goal_info.goal_id.uuid = uuid; auto future = cancel_client->async_send_request(request); if (rclcpp::executor::FutureReturnCode::SUCCESS != @@ -114,15 +114,15 @@ TEST_F(TestServer, handle_goal_called) // Create a client that calls the goal request service // Make sure the UUID received is the same as the one sent - auto client = node->create_client( + auto client = node->create_client( "fibonacci/_action/send_goal"); ASSERT_TRUE(client->wait_for_service(std::chrono::seconds(20))); - auto request = std::make_shared(); + auto request = std::make_shared(); const GoalID uuid{{1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16}}; - request->action_goal_id.uuid = uuid; + request->goal_id = uuid; auto future = client->async_send_request(request); ASSERT_EQ( @@ -164,7 +164,7 @@ TEST_F(TestServer, handle_accepted_called) ASSERT_TRUE(received_handle); ASSERT_TRUE(received_handle->is_active()); EXPECT_EQ(uuid, received_handle->get_goal_id()); - EXPECT_EQ(*request, *(received_handle->get_goal())); + EXPECT_EQ(request->goal, *(received_handle->get_goal())); } TEST_F(TestServer, handle_cancel_called) @@ -364,7 +364,7 @@ TEST_F(TestServer, publish_status_canceled) send_goal_request(node, uuid); send_cancel_request(node, uuid); - received_handle->set_canceled(std::make_shared()); + received_handle->set_canceled(std::make_shared()); // 10 seconds const size_t max_tries = 10 * 1000 / 100; @@ -419,7 +419,7 @@ TEST_F(TestServer, publish_status_succeeded) }); send_goal_request(node, uuid); - received_handle->set_succeeded(std::make_shared()); + received_handle->set_succeeded(std::make_shared()); // 10 seconds const size_t max_tries = 10 * 1000 / 100; @@ -474,7 +474,7 @@ TEST_F(TestServer, publish_status_aborted) }); send_goal_request(node, uuid); - received_handle->set_aborted(std::make_shared()); + received_handle->set_aborted(std::make_shared()); // 10 seconds const size_t max_tries = 10 * 1000 / 100; @@ -521,7 +521,7 @@ TEST_F(TestServer, publish_feedback) (void)as; // Subscribe to feedback messages - using FeedbackT = Fibonacci::Feedback; + using FeedbackT = Fibonacci::Impl::FeedbackMessage; std::vector received_msgs; auto subscriber = node->create_subscription( "fibonacci/_action/feedback", [&received_msgs](FeedbackT::SharedPtr msg) @@ -532,7 +532,7 @@ TEST_F(TestServer, publish_feedback) send_goal_request(node, uuid); auto sent_message = std::make_shared(); - sent_message->sequence = {1, 1, 2, 3, 5}; + sent_message->feedback.sequence = {1, 1, 2, 3, 5}; received_handle->publish_feedback(sent_message); // 10 seconds @@ -544,8 +544,7 @@ TEST_F(TestServer, publish_feedback) ASSERT_EQ(1u, received_msgs.size()); auto & msg = received_msgs.back(); - ASSERT_EQ(sent_message->sequence, msg->sequence); - ASSERT_EQ(uuid, msg->action_goal_id.uuid); + ASSERT_EQ(sent_message->feedback.sequence, msg->feedback.sequence); } TEST_F(TestServer, get_result) @@ -581,18 +580,18 @@ TEST_F(TestServer, get_result) send_goal_request(node, uuid); // Send result request - auto result_client = node->create_client( + auto result_client = node->create_client( "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(); - request->action_goal_id.uuid = uuid; + auto request = std::make_shared(); + request->goal_id = uuid; auto future = result_client->async_send_request(request); // Send a result - auto result = std::make_shared(); - result->sequence = {5, 8, 13, 21}; + auto result = std::make_shared(); + result->result.sequence = {5, 8, 13, 21}; received_handle->set_succeeded(result); // Wait for the result request to be received @@ -600,8 +599,8 @@ TEST_F(TestServer, get_result) rclcpp::spin_until_future_complete(node, future)); auto response = future.get(); - EXPECT_EQ(action_msgs::msg::GoalStatus::STATUS_SUCCEEDED, response->action_status); - EXPECT_EQ(result->sequence, response->sequence); + EXPECT_EQ(action_msgs::msg::GoalStatus::STATUS_SUCCEEDED, response->status); + EXPECT_EQ(result->result.sequence, response->result.sequence); } TEST_F(TestServer, deferred_execution) From f31fa242d2307a2f99caa875ad7dfcd4c0f1b6a2 Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Thu, 14 Feb 2019 15:55:12 -0800 Subject: [PATCH 02/10] fix action type casting --- rclcpp_action/include/rclcpp_action/server.hpp | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/rclcpp_action/include/rclcpp_action/server.hpp b/rclcpp_action/include/rclcpp_action/server.hpp index 8288f6a090..d25639aecd 100644 --- a/rclcpp_action/include/rclcpp_action/server.hpp +++ b/rclcpp_action/include/rclcpp_action/server.hpp @@ -337,8 +337,10 @@ class Server : public ServerBase, public std::enable_shared_from_this> call_handle_goal_callback(GoalID & uuid, std::shared_ptr message) override { - GoalResponse user_response = handle_goal_( - uuid, std::static_pointer_cast(message)); + auto request = std::static_pointer_cast< + typename ActionT::Impl::SendGoalService::Request>(message); + auto goal = std::shared_ptr(request, &request->goal); + GoalResponse user_response = handle_goal_(uuid, goal); auto ros_response = std::make_shared(); ros_response->accepted = GoalResponse::ACCEPT_AND_EXECUTE == user_response || @@ -414,11 +416,12 @@ class Server : public ServerBase, public std::enable_shared_from_thispublish_feedback(std::static_pointer_cast(feedback_msg)); }; + auto request = std::static_pointer_cast< + const typename ActionT::Impl::SendGoalService::Request>(goal_request_message); + auto goal = std::shared_ptr(request, &request->goal); goal_handle.reset( new ServerGoalHandle( - rcl_goal_handle, uuid, - std::static_pointer_cast(goal_request_message), - on_terminal_state, on_executing, publish_feedback)); + rcl_goal_handle, uuid, goal, on_terminal_state, on_executing, publish_feedback)); { std::lock_guard lock(goal_handles_mutex_); goal_handles_[uuid] = goal_handle; From 5a549be46b4d4c308e80ec87462dbcbcf0dfe937 Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Fri, 15 Feb 2019 14:31:11 -0800 Subject: [PATCH 03/10] rename type/field to use correct term --- rclcpp_action/include/rclcpp_action/client.hpp | 16 ++++++++-------- .../include/rclcpp_action/client_goal_handle.hpp | 14 +++++++------- .../rclcpp_action/client_goal_handle_impl.hpp | 8 ++++---- .../include/rclcpp_action/server_goal_handle.hpp | 4 ++-- rclcpp_action/test/test_client.cpp | 16 ++++++++-------- 5 files changed, 29 insertions(+), 29 deletions(-) diff --git a/rclcpp_action/include/rclcpp_action/client.hpp b/rclcpp_action/include/rclcpp_action/client.hpp index 79273542ac..1bf8041b04 100644 --- a/rclcpp_action/include/rclcpp_action/client.hpp +++ b/rclcpp_action/include/rclcpp_action/client.hpp @@ -260,7 +260,7 @@ class Client : public ClientBase using Goal = typename ActionT::Goal; using Feedback = typename ActionT::Feedback; using GoalHandle = ClientGoalHandle; - using Result = typename GoalHandle::Result; + using WrappedResult = typename GoalHandle::WrappedResult; using FeedbackCallback = typename ClientGoalHandle::FeedbackCallback; using CancelRequest = typename ActionT::Impl::CancelGoalService::Request; using CancelResponse = typename ActionT::Impl::CancelGoalService::Response; @@ -322,7 +322,7 @@ class Client : public ClientBase return future; } - std::shared_future + std::shared_future async_get_result(typename GoalHandle::SharedPtr goal_handle) { std::lock_guard lock(goal_handles_mutex_); @@ -502,14 +502,14 @@ class Client : public ClientBase [goal_handle, this](std::shared_ptr response) mutable { // Wrap the response in a struct with the fields a user cares about - Result result; + WrappedResult wrapped_result; using GoalResultResponse = typename ActionT::Impl::GetResultService::Response; auto result_response = std::static_pointer_cast(response); - result.response = std::make_shared(); - *result.response = result_response->result; - result.goal_id = goal_handle->get_goal_id(); - result.code = static_cast(result_response->status); - goal_handle->set_result(result); + wrapped_result.result = std::make_shared(); + *wrapped_result.result = result_response->result; + wrapped_result.goal_id = goal_handle->get_goal_id(); + wrapped_result.code = static_cast(result_response->status); + goal_handle->set_result(wrapped_result); std::lock_guard lock(goal_handles_mutex_); goal_handles_.erase(goal_handle->get_goal_id()); }); diff --git a/rclcpp_action/include/rclcpp_action/client_goal_handle.hpp b/rclcpp_action/include/rclcpp_action/client_goal_handle.hpp index 8fb629c87f..a77cc6ed36 100644 --- a/rclcpp_action/include/rclcpp_action/client_goal_handle.hpp +++ b/rclcpp_action/include/rclcpp_action/client_goal_handle.hpp @@ -52,15 +52,15 @@ class ClientGoalHandle RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(ClientGoalHandle) // A wrapper that defines the result of an action - typedef struct Result + typedef struct WrappedResult { /// The unique identifier of the goal GoalID goal_id; /// A status to indicate if the goal was canceled, aborted, or suceeded ResultCode code; /// User defined fields sent back with an action - typename ActionT::Result::SharedPtr response; - } Result; + typename ActionT::Result::SharedPtr result; + } WrappedResult; using Feedback = typename ActionT::Feedback; using FeedbackCallback = @@ -76,7 +76,7 @@ class ClientGoalHandle rclcpp::Time get_goal_stamp() const; - std::shared_future + std::shared_future async_result(); int8_t @@ -109,7 +109,7 @@ class ClientGoalHandle set_status(int8_t status); void - set_result(const Result & result); + set_result(const WrappedResult & wrapped_result); void invalidate(); @@ -117,8 +117,8 @@ class ClientGoalHandle GoalInfo info_; bool is_result_aware_{false}; - std::promise result_promise_; - std::shared_future result_future_; + std::promise result_promise_; + std::shared_future result_future_; FeedbackCallback feedback_callback_{nullptr}; int8_t status_{GoalStatus::STATUS_ACCEPTED}; diff --git a/rclcpp_action/include/rclcpp_action/client_goal_handle_impl.hpp b/rclcpp_action/include/rclcpp_action/client_goal_handle_impl.hpp index 3cf7960a33..87fa6af663 100644 --- a/rclcpp_action/include/rclcpp_action/client_goal_handle_impl.hpp +++ b/rclcpp_action/include/rclcpp_action/client_goal_handle_impl.hpp @@ -54,7 +54,7 @@ ClientGoalHandle::get_goal_stamp() const } template -std::shared_future::Result> +std::shared_future::WrappedResult> ClientGoalHandle::async_result() { std::lock_guard guard(handle_mutex_); @@ -66,11 +66,11 @@ ClientGoalHandle::async_result() template void -ClientGoalHandle::set_result(const Result & result) +ClientGoalHandle::set_result(const WrappedResult & wrapped_result) { std::lock_guard guard(handle_mutex_); - status_ = static_cast(result.code); - result_promise_.set_value(result); + status_ = static_cast(wrapped_result.code); + result_promise_.set_value(wrapped_result); } template diff --git a/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp b/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp index 00aecdd718..6d33fe8267 100644 --- a/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp +++ b/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp @@ -215,7 +215,7 @@ class ServerGoalHandle : public ServerGoalHandleBase on_executing_(uuid_); } - /// Get the original request message describing the goal. + /// Get the user provided message describing the goal. const std::shared_ptr get_goal() const { @@ -255,7 +255,7 @@ class ServerGoalHandle : public ServerGoalHandleBase { } - /// The original request message describing the goal. + /// The user provided message describing the goal. const std::shared_ptr goal_; /// A unique id for the goal request. diff --git a/rclcpp_action/test/test_client.cpp b/rclcpp_action/test/test_client.cpp index 422b9d9d84..8720d0f178 100644 --- a/rclcpp_action/test/test_client.cpp +++ b/rclcpp_action/test/test_client.cpp @@ -305,11 +305,11 @@ TEST_F(TestClient, async_send_goal_and_ignore_feedback_but_wait_for_result) EXPECT_TRUE(goal_handle->is_result_aware()); auto future_result = goal_handle->async_result(); dual_spin_until_future_complete(future_result); - auto result = future_result.get(); - ASSERT_EQ(6ul, result.response->sequence.size()); - EXPECT_EQ(0, result.response->sequence[0]); - EXPECT_EQ(1, result.response->sequence[1]); - EXPECT_EQ(5, result.response->sequence[5]); + auto wrapped_result = future_result.get(); + ASSERT_EQ(6ul, wrapped_result.result->sequence.size()); + EXPECT_EQ(0, wrapped_result.result->sequence[0]); + EXPECT_EQ(1, wrapped_result.result->sequence[1]); + EXPECT_EQ(5, wrapped_result.result->sequence[5]); } TEST_F(TestClient, async_send_goal_with_feedback_and_result) @@ -337,10 +337,10 @@ TEST_F(TestClient, async_send_goal_with_feedback_and_result) EXPECT_TRUE(goal_handle->is_result_aware()); auto future_result = goal_handle->async_result(); dual_spin_until_future_complete(future_result); - auto result = future_result.get(); + auto wrapped_result = future_result.get(); - ASSERT_EQ(5u, result.response->sequence.size()); - EXPECT_EQ(3, result.response->sequence.back()); + ASSERT_EQ(5u, wrapped_result.result->sequence.size()); + EXPECT_EQ(3, wrapped_result.result->sequence.back()); EXPECT_EQ(5, feedback_count); } From 29c5da97002167eb65e1c3b455f9cb8fe9fb9772 Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Sun, 17 Feb 2019 21:22:07 -0800 Subject: [PATCH 04/10] rename custom GoalID type to avoid naming collision, update types using unique_identifier_msgs --- .../include/rclcpp_action/client.hpp | 17 +++--- .../rclcpp_action/client_goal_handle.hpp | 4 +- .../rclcpp_action/client_goal_handle_impl.hpp | 2 +- .../include/rclcpp_action/server.hpp | 38 ++++++------ .../rclcpp_action/server_goal_handle.hpp | 16 ++--- rclcpp_action/include/rclcpp_action/types.hpp | 18 +++--- rclcpp_action/src/client.cpp | 4 +- rclcpp_action/src/server.cpp | 18 +++--- rclcpp_action/src/types.cpp | 6 +- rclcpp_action/test/test_client.cpp | 22 +++---- rclcpp_action/test/test_server.cpp | 60 +++++++++---------- 11 files changed, 102 insertions(+), 103 deletions(-) diff --git a/rclcpp_action/include/rclcpp_action/client.hpp b/rclcpp_action/include/rclcpp_action/client.hpp index 1bf8041b04..1fd2aa024d 100644 --- a/rclcpp_action/include/rclcpp_action/client.hpp +++ b/rclcpp_action/include/rclcpp_action/client.hpp @@ -148,7 +148,7 @@ class ClientBase : public rclcpp::Waitable /// \internal RCLCPP_ACTION_PUBLIC virtual - GoalID + GoalUUID generate_goal_id(); /// \internal @@ -288,7 +288,7 @@ class Client : public ClientBase std::shared_future future(promise->get_future()); using GoalRequest = typename ActionT::Impl::SendGoalService::Request; auto goal_request = std::make_shared(); - goal_request->goal_id = this->generate_goal_id(); + goal_request->goal_id.uuid = this->generate_goal_id(); goal_request->goal = goal; this->send_goal_request( std::static_pointer_cast(goal_request), @@ -302,8 +302,7 @@ class Client : public ClientBase return; } GoalInfo goal_info; - // goal_info.goal_id = goal_request->goal_id; - goal_info.goal_id.uuid = goal_request->goal_id; + goal_info.goal_id.uuid = goal_request->goal_id.uuid; goal_info.stamp = goal_response->stamp; // Do not use std::make_shared as friendship cannot be forwarded. std::shared_ptr goal_handle(new GoalHandle(goal_info, callback)); @@ -439,7 +438,7 @@ class Client : public ClientBase using FeedbackMessage = typename ActionT::Impl::FeedbackMessage; typename FeedbackMessage::SharedPtr feedback_message = std::static_pointer_cast(message); - const GoalID & goal_id = feedback_message->goal_id; + const GoalUUID & goal_id = feedback_message->goal_id.uuid; if (goal_handles_.count(goal_id) == 0) { RCLCPP_DEBUG( this->get_logger(), @@ -468,8 +467,8 @@ class Client : public ClientBase using GoalStatusMessage = typename ActionT::Impl::GoalStatusMessage; auto status_message = std::static_pointer_cast(message); for (const GoalStatus & status : status_message->status_list) { - // const GoalID & goal_id = status.goal_info.goal_id; - const GoalID & goal_id = status.goal_info.goal_id.uuid; + // const GoalUUID & goal_id = status.goal_info.goal_id; + const GoalUUID & goal_id = status.goal_info.goal_id.uuid; if (goal_handles_.count(goal_id) == 0) { RCLCPP_DEBUG( this->get_logger(), @@ -496,7 +495,7 @@ class Client : public ClientBase using GoalResultRequest = typename ActionT::Impl::GetResultService::Request; auto goal_result_request = std::make_shared(); // goal_result_request.goal_id = goal_handle->get_goal_id(); - goal_result_request->goal_id = goal_handle->get_goal_id(); + goal_result_request->goal_id.uuid = goal_handle->get_goal_id(); this->send_result_request( std::static_pointer_cast(goal_result_request), [goal_handle, this](std::shared_ptr response) mutable @@ -533,7 +532,7 @@ class Client : public ClientBase return future; } - std::map goal_handles_; + std::map goal_handles_; std::mutex goal_handles_mutex_; }; } // namespace rclcpp_action diff --git a/rclcpp_action/include/rclcpp_action/client_goal_handle.hpp b/rclcpp_action/include/rclcpp_action/client_goal_handle.hpp index a77cc6ed36..bee86b55c7 100644 --- a/rclcpp_action/include/rclcpp_action/client_goal_handle.hpp +++ b/rclcpp_action/include/rclcpp_action/client_goal_handle.hpp @@ -55,7 +55,7 @@ class ClientGoalHandle typedef struct WrappedResult { /// The unique identifier of the goal - GoalID goal_id; + GoalUUID goal_id; /// A status to indicate if the goal was canceled, aborted, or suceeded ResultCode code; /// User defined fields sent back with an action @@ -70,7 +70,7 @@ class ClientGoalHandle virtual ~ClientGoalHandle(); - const GoalID & + const GoalUUID & get_goal_id() const; rclcpp::Time diff --git a/rclcpp_action/include/rclcpp_action/client_goal_handle_impl.hpp b/rclcpp_action/include/rclcpp_action/client_goal_handle_impl.hpp index 87fa6af663..73f850dd47 100644 --- a/rclcpp_action/include/rclcpp_action/client_goal_handle_impl.hpp +++ b/rclcpp_action/include/rclcpp_action/client_goal_handle_impl.hpp @@ -39,7 +39,7 @@ ClientGoalHandle::~ClientGoalHandle() } template -const GoalID & +const GoalUUID & ClientGoalHandle::get_goal_id() const { // return info_.goal_id; diff --git a/rclcpp_action/include/rclcpp_action/server.hpp b/rclcpp_action/include/rclcpp_action/server.hpp index d25639aecd..4a9cff0b1d 100644 --- a/rclcpp_action/include/rclcpp_action/server.hpp +++ b/rclcpp_action/include/rclcpp_action/server.hpp @@ -146,7 +146,7 @@ class ServerBase : public rclcpp::Waitable RCLCPP_ACTION_PUBLIC virtual std::pair> - call_handle_goal_callback(GoalID &, std::shared_ptr request) = 0; + call_handle_goal_callback(GoalUUID &, std::shared_ptr request) = 0; // ServerBase will determine which goal ids are being cancelled, and then call this function for // each goal id. @@ -155,13 +155,13 @@ class ServerBase : public rclcpp::Waitable RCLCPP_ACTION_PUBLIC virtual CancelResponse - call_handle_cancel_callback(const GoalID & uuid) = 0; + call_handle_cancel_callback(const GoalUUID & uuid) = 0; /// Given a goal request message, return the UUID contained within. /// \internal RCLCPP_ACTION_PUBLIC virtual - GoalID + GoalUUID get_goal_id_from_goal_request(void * message) = 0; /// Create an empty goal request message so it can be taken from a lower layer. @@ -178,13 +178,13 @@ class ServerBase : public rclcpp::Waitable void call_goal_accepted_callback( std::shared_ptr rcl_goal_handle, - GoalID uuid, std::shared_ptr goal_request_message) = 0; + GoalUUID uuid, std::shared_ptr goal_request_message) = 0; /// Given a result request message, return the UUID contained within. /// \internal RCLCPP_ACTION_PUBLIC virtual - GoalID + GoalUUID get_goal_id_from_result_request(void * message) = 0; /// Create an empty goal request message so it can be taken from a lower layer. @@ -214,7 +214,7 @@ class ServerBase : public rclcpp::Waitable /// \internal RCLCPP_ACTION_PUBLIC void - publish_result(const GoalID & uuid, std::shared_ptr result_msg); + publish_result(const GoalUUID & uuid, std::shared_ptr result_msg); /// \internal RCLCPP_ACTION_PUBLIC @@ -272,7 +272,7 @@ class Server : public ServerBase, public std::enable_shared_from_this)>; + const GoalUUID &, std::shared_ptr)>; /// Signature of a callback that accepts or rejects requests to cancel a goal. using CancelCallback = std::function>)>; /// Signature of a callback that is used to notify when the goal has been accepted. @@ -335,7 +335,7 @@ class Server : public ServerBase, public std::enable_shared_from_this> - call_handle_goal_callback(GoalID & uuid, std::shared_ptr message) override + call_handle_goal_callback(GoalUUID & uuid, std::shared_ptr message) override { auto request = std::static_pointer_cast< typename ActionT::Impl::SendGoalService::Request>(message); @@ -350,7 +350,7 @@ class Server : public ServerBase, public std::enable_shared_from_this lock(goal_handles_mutex_); CancelResponse resp = CancelResponse::REJECT; @@ -371,13 +371,13 @@ class Server : public ServerBase, public std::enable_shared_from_this rcl_goal_handle, - GoalID uuid, std::shared_ptr goal_request_message) override + GoalUUID uuid, std::shared_ptr goal_request_message) override { std::shared_ptr> goal_handle; std::weak_ptr> weak_this = this->shared_from_this(); - std::function)> on_terminal_state = - [weak_this](const GoalID & uuid, std::shared_ptr result_message) + std::function)> on_terminal_state = + [weak_this](const GoalUUID & uuid, std::shared_ptr result_message) { std::shared_ptr> shared_this = weak_this.lock(); if (!shared_this) { @@ -394,8 +394,8 @@ class Server : public ServerBase, public std::enable_shared_from_thisgoal_handles_.erase(uuid); }; - std::function on_executing = - [weak_this](const GoalID & uuid) + std::function on_executing = + [weak_this](const GoalUUID & uuid) { std::shared_ptr> shared_this = weak_this.lock(); if (!shared_this) { @@ -430,11 +430,11 @@ class Server : public ServerBase, public std::enable_shared_from_this(message)->goal_id; + static_cast(message)->goal_id.uuid; } /// \internal @@ -445,11 +445,11 @@ class Server : public ServerBase, public std::enable_shared_from_this(message)->goal_id; + static_cast(message)->goal_id.uuid; } /// \internal @@ -479,7 +479,7 @@ class Server : public ServerBase, public std::enable_shared_from_this>; /// A map of goal id to goal handle weak pointers. /// This is used to provide a goal handle to handle_cancel. - std::unordered_map goal_handles_; + std::unordered_map goal_handles_; std::mutex goal_handles_mutex_; }; } // namespace rclcpp_action diff --git a/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp b/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp index 6d33fe8267..4257f89a53 100644 --- a/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp +++ b/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp @@ -147,7 +147,7 @@ class ServerGoalHandle : public ServerGoalHandleBase void publish_feedback(std::shared_ptr feedback_msg) { - feedback_msg->goal_id = uuid_; + feedback_msg->goal_id.uuid = uuid_; publish_feedback_(feedback_msg); } @@ -223,7 +223,7 @@ class ServerGoalHandle : public ServerGoalHandleBase } /// Get the unique identifier of the goal - const GoalID & + const GoalUUID & get_goal_id() const { return uuid_; @@ -243,10 +243,10 @@ class ServerGoalHandle : public ServerGoalHandleBase /// \internal ServerGoalHandle( std::shared_ptr rcl_handle, - GoalID uuid, + GoalUUID uuid, std::shared_ptr goal, - std::function)> on_terminal_state, - std::function on_executing, + std::function)> on_terminal_state, + std::function on_executing, std::function)> publish_feedback ) : ServerGoalHandleBase(rcl_handle), goal_(goal), uuid_(uuid), @@ -259,12 +259,12 @@ class ServerGoalHandle : public ServerGoalHandleBase const std::shared_ptr goal_; /// A unique id for the goal request. - const GoalID uuid_; + const GoalUUID uuid_; friend Server; - std::function)> on_terminal_state_; - std::function on_executing_; + std::function)> on_terminal_state_; + std::function on_executing_; std::function)> publish_feedback_; }; } // namespace rclcpp_action diff --git a/rclcpp_action/include/rclcpp_action/types.hpp b/rclcpp_action/include/rclcpp_action/types.hpp index badfdbdff3..addf4a8307 100644 --- a/rclcpp_action/include/rclcpp_action/types.hpp +++ b/rclcpp_action/include/rclcpp_action/types.hpp @@ -29,34 +29,34 @@ namespace rclcpp_action { -using GoalID = std::array; +using GoalUUID = std::array; using GoalStatus = action_msgs::msg::GoalStatus; using GoalInfo = action_msgs::msg::GoalInfo; /// Convert a goal id to a human readable string. RCLCPP_ACTION_PUBLIC std::string -to_string(const GoalID & goal_id); +to_string(const GoalUUID & goal_id); // Convert C++ GoalID to rcl_action_goal_info_t RCLCPP_ACTION_PUBLIC void -convert(const GoalID & goal_id, rcl_action_goal_info_t * info); +convert(const GoalUUID & goal_id, rcl_action_goal_info_t * info); // Convert rcl_action_goal_info_t to C++ GoalID RCLCPP_ACTION_PUBLIC void -convert(const rcl_action_goal_info_t & info, GoalID * goal_id); +convert(const rcl_action_goal_info_t & info, GoalUUID * goal_id); } // namespace rclcpp_action namespace std { template<> -struct less +struct less { bool operator()( - const rclcpp_action::GoalID & lhs, - const rclcpp_action::GoalID & rhs) const + const rclcpp_action::GoalUUID & lhs, + const rclcpp_action::GoalUUID & rhs) const { return lhs < rhs; } @@ -64,9 +64,9 @@ struct less /// Hash a goal id so it can be used as a key in std::unordered_map template<> -struct hash +struct hash { - size_t operator()(const rclcpp_action::GoalID & uuid) const noexcept + size_t operator()(const rclcpp_action::GoalUUID & uuid) const noexcept { // TODO(sloretz) Use someone else's hash function and cite it size_t result = 0; diff --git a/rclcpp_action/src/client.cpp b/rclcpp_action/src/client.cpp index e3f1198dcc..3a34f35195 100644 --- a/rclcpp_action/src/client.cpp +++ b/rclcpp_action/src/client.cpp @@ -366,10 +366,10 @@ ClientBase::send_cancel_request(std::shared_ptr request, ResponseCallback pimpl_->pending_cancel_responses[sequence_number] = callback; } -GoalID +GoalUUID ClientBase::generate_goal_id() { - GoalID goal_id; + GoalUUID goal_id; // TODO(hidmic): Do something better than this for UUID generation. // std::generate( // goal_id.uuid.begin(), goal_id.uuid.end(), diff --git a/rclcpp_action/src/server.cpp b/rclcpp_action/src/server.cpp index ac787a4bcc..025495db54 100644 --- a/rclcpp_action/src/server.cpp +++ b/rclcpp_action/src/server.cpp @@ -28,7 +28,7 @@ #include using rclcpp_action::ServerBase; -using rclcpp_action::GoalID; +using rclcpp_action::GoalUUID; namespace rclcpp_action { @@ -62,11 +62,11 @@ class ServerBaseImpl bool goal_expired_ = false; // Results to be kept until the goal expires after reaching a terminal state - std::unordered_map> goal_results_; + std::unordered_map> goal_results_; // Requests for results are kept until a result becomes available - std::unordered_map> result_requests_; + std::unordered_map> result_requests_; // rcl goal handles are kept so api to send result doesn't try to access freed memory - std::unordered_map> goal_handles_; + std::unordered_map> goal_handles_; rclcpp::Logger logger_; }; @@ -228,7 +228,7 @@ ServerBase::execute_goal_request_received() rclcpp::exceptions::throw_from_rcl_error(ret); } - GoalID uuid = get_goal_id_from_goal_request(message.get()); + GoalUUID uuid = get_goal_id_from_goal_request(message.get()); convert(uuid, &goal_info); // Call user's callback, getting the user's response and a ros message to send back @@ -339,7 +339,7 @@ ServerBase::execute_cancel_request_received() // For each canceled goal, call cancel callback for (size_t i = 0; i < goals.size; ++i) { const rcl_action_goal_info_t & goal_info = goals.data[i]; - GoalID uuid; + GoalUUID uuid; convert(goal_info, &uuid); auto response_code = call_handle_cancel_callback(uuid); if (CancelResponse::ACCEPT == response_code) { @@ -388,7 +388,7 @@ ServerBase::execute_result_request_received() std::shared_ptr result_response; // check if the goal exists - GoalID uuid = get_goal_id_from_result_request(result_request.get()); + GoalUUID uuid = get_goal_id_from_result_request(result_request.get()); rcl_action_goal_info_t goal_info; convert(uuid, &goal_info); bool goal_exists; @@ -433,7 +433,7 @@ ServerBase::execute_check_expired_goals() rclcpp::exceptions::throw_from_rcl_error(ret); } else if (num_expired) { // A goal expired! - GoalID uuid; + GoalUUID uuid; convert(expired_goals[0], &uuid); RCLCPP_DEBUG(pimpl_->logger_, "Expired goal %s", to_string(uuid).c_str()); pimpl_->goal_results_.erase(uuid); @@ -497,7 +497,7 @@ ServerBase::publish_status() } void -ServerBase::publish_result(const GoalID & uuid, std::shared_ptr result_msg) +ServerBase::publish_result(const GoalUUID & uuid, std::shared_ptr result_msg) { // Check that the goal exists rcl_action_goal_info_t goal_info; diff --git a/rclcpp_action/src/types.cpp b/rclcpp_action/src/types.cpp index cc2779bd18..773702789e 100644 --- a/rclcpp_action/src/types.cpp +++ b/rclcpp_action/src/types.cpp @@ -20,7 +20,7 @@ namespace rclcpp_action { std::string -to_string(const GoalID & goal_id) +to_string(const GoalUUID & goal_id) { std::stringstream stream; stream << std::hex; @@ -31,7 +31,7 @@ to_string(const GoalID & goal_id) } void -convert(const GoalID & goal_id, rcl_action_goal_info_t * info) +convert(const GoalUUID & goal_id, rcl_action_goal_info_t * info) { for (size_t i = 0; i < 16; ++i) { info->goal_id.uuid[i] = goal_id[i]; @@ -39,7 +39,7 @@ convert(const GoalID & goal_id, rcl_action_goal_info_t * info) } void -convert(const rcl_action_goal_info_t & info, GoalID * goal_id) +convert(const rcl_action_goal_info_t & info, GoalUUID * goal_id) { for (size_t i = 0; i < 16; ++i) { (*goal_id)[i] = info.goal_id.uuid[i]; diff --git a/rclcpp_action/test/test_client.cpp b/rclcpp_action/test/test_client.cpp index 8720d0f178..32afe75310 100644 --- a/rclcpp_action/test/test_client.cpp +++ b/rclcpp_action/test/test_client.cpp @@ -91,7 +91,7 @@ class TestClient : public ::testing::Test response->stamp = clock.now(); response->accepted = (request->goal.order >= 0); if (response->accepted) { - goals[request->goal_id] = {request, response}; + goals[request->goal_id.uuid] = {request, response}; } }); ASSERT_TRUE(goal_service != nullptr); @@ -107,19 +107,19 @@ class TestClient : public ::testing::Test const ActionGoalResultRequest::SharedPtr request, ActionGoalResultResponse::SharedPtr response) { - if (goals.count(request->goal_id) == 1) { - auto goal_request = goals[request->goal_id].first; - auto goal_response = goals[request->goal_id].second; + if (goals.count(request->goal_id.uuid) == 1) { + auto goal_request = goals[request->goal_id.uuid].first; + auto goal_response = goals[request->goal_id.uuid].second; ActionStatusMessage status_message; rclcpp_action::GoalStatus goal_status; - goal_status.goal_info.goal_id.uuid = goal_request->goal_id; + goal_status.goal_info.goal_id.uuid = goal_request->goal_id.uuid; goal_status.goal_info.stamp = goal_response->stamp; goal_status.status = rclcpp_action::GoalStatus::STATUS_EXECUTING; status_message.status_list.push_back(goal_status); status_publisher->publish(status_message); client_executor.spin_once(); ActionFeedbackMessage feedback_message; - feedback_message.goal_id = goal_request->goal_id; + feedback_message.goal_id.uuid = goal_request->goal_id.uuid; feedback_message.feedback.sequence.push_back(0); feedback_publisher->publish(feedback_message); client_executor.spin_once(); @@ -141,7 +141,7 @@ class TestClient : public ::testing::Test client_executor.spin_once(); response->result.sequence = feedback_message.feedback.sequence; response->status = rclcpp_action::GoalStatus::STATUS_SUCCEEDED; - goals.erase(request->goal_id); + goals.erase(request->goal_id.uuid); } else { response->status = rclcpp_action::GoalStatus::STATUS_UNKNOWN; } @@ -159,7 +159,7 @@ class TestClient : public ::testing::Test const ActionCancelGoalRequest::SharedPtr request, ActionCancelGoalResponse::SharedPtr response) { - rclcpp_action::GoalID zero_uuid; + rclcpp_action::GoalUUID zero_uuid; std::fill(zero_uuid.begin(), zero_uuid.end(), 0u); const rclcpp::Time cancel_stamp = request->goal_info.stamp; bool cancel_all = ( @@ -172,11 +172,11 @@ class TestClient : public ::testing::Test auto goal_response = it->second.second; const rclcpp::Time goal_stamp = goal_response->stamp; bool cancel_this = ( - request->goal_info.goal_id.uuid == goal_request->goal_id || + request->goal_info.goal_id.uuid == goal_request->goal_id.uuid || cancel_stamp > goal_stamp); if (cancel_all || cancel_this) { rclcpp_action::GoalStatus goal_status; - goal_status.goal_info.goal_id.uuid = goal_request->goal_id; + goal_status.goal_info.goal_id.uuid = goal_request->goal_id.uuid; goal_status.goal_info.stamp = goal_response->stamp; goal_status.status = rclcpp_action::GoalStatus::STATUS_CANCELED; status_message.status_list.push_back(goal_status); @@ -252,7 +252,7 @@ class TestClient : public ::testing::Test const char * const action_name{"fibonacci_test"}; std::map< - rclcpp_action::GoalID, + rclcpp_action::GoalUUID, std::pair< typename ActionGoalRequest::SharedPtr, typename ActionGoalResponse::SharedPtr>> goals; diff --git a/rclcpp_action/test/test_server.cpp b/rclcpp_action/test/test_server.cpp index 23c3a49a0d..8c94c82cda 100644 --- a/rclcpp_action/test/test_server.cpp +++ b/rclcpp_action/test/test_server.cpp @@ -26,7 +26,7 @@ #include "rclcpp_action/server.hpp" using Fibonacci = test_msgs::action::Fibonacci; -using GoalID = rclcpp_action::GoalID; +using GoalUUID = rclcpp_action::GoalUUID; class TestServer : public ::testing::Test { @@ -37,7 +37,7 @@ class TestServer : public ::testing::Test } std::shared_ptr - send_goal_request(rclcpp::Node::SharedPtr node, GoalID uuid) + send_goal_request(rclcpp::Node::SharedPtr node, GoalUUID uuid) { auto client = node->create_client( "fibonacci/_action/send_goal"); @@ -45,7 +45,7 @@ class TestServer : public ::testing::Test throw std::runtime_error("send goal service didn't become available"); } auto request = std::make_shared(); - request->goal_id = uuid; + request->goal_id.uuid = uuid; auto future = client->async_send_request(request); if (rclcpp::executor::FutureReturnCode::SUCCESS != rclcpp::spin_until_future_complete(node, future)) @@ -56,7 +56,7 @@ class TestServer : public ::testing::Test } void - send_cancel_request(rclcpp::Node::SharedPtr node, GoalID uuid) + send_cancel_request(rclcpp::Node::SharedPtr node, GoalUUID uuid) { auto cancel_client = node->create_client( "fibonacci/_action/cancel_goal"); @@ -80,7 +80,7 @@ TEST_F(TestServer, construction_and_destruction) using GoalHandle = rclcpp_action::ServerGoalHandle; auto as = rclcpp_action::create_server(node, "fibonacci", - [](const GoalID &, std::shared_ptr) { + [](const GoalUUID &, std::shared_ptr) { return rclcpp_action::GoalResponse::REJECT; }, [](std::shared_ptr) { @@ -93,10 +93,10 @@ TEST_F(TestServer, construction_and_destruction) TEST_F(TestServer, handle_goal_called) { auto node = std::make_shared("handle_goal_node", "/rclcpp_action/handle_goal"); - GoalID received_uuid; + GoalUUID received_uuid; auto handle_goal = [&received_uuid]( - const GoalID & uuid, std::shared_ptr) + const GoalUUID & uuid, std::shared_ptr) { received_uuid = uuid; return rclcpp_action::GoalResponse::REJECT; @@ -121,8 +121,8 @@ TEST_F(TestServer, handle_goal_called) auto request = std::make_shared(); - const GoalID uuid{{1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16}}; - request->goal_id = uuid; + const GoalUUID uuid{{1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16}}; + request->goal_id.uuid = uuid; auto future = client->async_send_request(request); ASSERT_EQ( @@ -135,10 +135,10 @@ TEST_F(TestServer, handle_goal_called) TEST_F(TestServer, handle_accepted_called) { auto node = std::make_shared("handle_exec_node", "/rclcpp_action/handle_accepted"); - const GoalID uuid{{1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16}}; + const GoalUUID uuid{{1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16}}; auto handle_goal = []( - const GoalID &, std::shared_ptr) + const GoalUUID &, std::shared_ptr) { return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; }; @@ -170,10 +170,10 @@ TEST_F(TestServer, handle_accepted_called) TEST_F(TestServer, handle_cancel_called) { auto node = std::make_shared("handle_cancel_node", "/rclcpp_action/handle_cancel"); - const GoalID uuid{{10, 20, 30, 40, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16}}; + const GoalUUID uuid{{10, 20, 30, 40, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16}}; auto handle_goal = []( - const GoalID &, std::shared_ptr) + const GoalUUID &, std::shared_ptr) { return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; }; @@ -210,10 +210,10 @@ TEST_F(TestServer, handle_cancel_called) TEST_F(TestServer, publish_status_accepted) { auto node = std::make_shared("status_accept_node", "/rclcpp_action/status_accept"); - const GoalID uuid{{1, 2, 3, 4, 5, 6, 7, 8, 9, 100, 110, 120, 13, 14, 15, 16}}; + const GoalUUID uuid{{1, 2, 3, 4, 5, 6, 7, 8, 9, 100, 110, 120, 13, 14, 15, 16}}; auto handle_goal = []( - const GoalID &, std::shared_ptr) + const GoalUUID &, std::shared_ptr) { return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; }; @@ -271,10 +271,10 @@ TEST_F(TestServer, publish_status_accepted) TEST_F(TestServer, publish_status_canceling) { auto node = std::make_shared("status_cancel_node", "/rclcpp_action/status_cancel"); - const GoalID uuid{{1, 2, 3, 40, 5, 6, 7, 80, 9, 10, 11, 120, 13, 14, 15, 160}}; + const GoalUUID uuid{{1, 2, 3, 40, 5, 6, 7, 80, 9, 10, 11, 120, 13, 14, 15, 160}}; auto handle_goal = []( - const GoalID &, std::shared_ptr) + const GoalUUID &, std::shared_ptr) { return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; }; @@ -326,10 +326,10 @@ TEST_F(TestServer, publish_status_canceling) TEST_F(TestServer, publish_status_canceled) { auto node = std::make_shared("status_canceled", "/rclcpp_action/status_canceled"); - const GoalID uuid{{1, 2, 3, 40, 5, 6, 70, 8, 9, 1, 11, 120, 13, 140, 15, 160}}; + const GoalUUID uuid{{1, 2, 3, 40, 5, 6, 70, 8, 9, 1, 11, 120, 13, 140, 15, 160}}; auto handle_goal = []( - const GoalID &, std::shared_ptr) + const GoalUUID &, std::shared_ptr) { return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; }; @@ -383,10 +383,10 @@ TEST_F(TestServer, publish_status_canceled) TEST_F(TestServer, publish_status_succeeded) { auto node = std::make_shared("status_succeeded", "/rclcpp_action/status_succeeded"); - const GoalID uuid{{1, 2, 3, 40, 5, 6, 70, 8, 9, 1, 11, 120, 13, 140, 15, 160}}; + const GoalUUID uuid{{1, 2, 3, 40, 5, 6, 70, 8, 9, 1, 11, 120, 13, 140, 15, 160}}; auto handle_goal = []( - const GoalID &, std::shared_ptr) + const GoalUUID &, std::shared_ptr) { return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; }; @@ -438,10 +438,10 @@ TEST_F(TestServer, publish_status_succeeded) TEST_F(TestServer, publish_status_aborted) { auto node = std::make_shared("status_aborted", "/rclcpp_action/status_aborted"); - const GoalID uuid{{1, 2, 3, 40, 5, 6, 70, 8, 9, 1, 11, 120, 13, 140, 15, 160}}; + const GoalUUID uuid{{1, 2, 3, 40, 5, 6, 70, 8, 9, 1, 11, 120, 13, 140, 15, 160}}; auto handle_goal = []( - const GoalID &, std::shared_ptr) + const GoalUUID &, std::shared_ptr) { return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; }; @@ -493,10 +493,10 @@ TEST_F(TestServer, publish_status_aborted) TEST_F(TestServer, publish_feedback) { auto node = std::make_shared("pub_feedback", "/rclcpp_action/pub_feedback"); - const GoalID uuid{{1, 20, 30, 4, 5, 6, 70, 8, 9, 1, 11, 120, 13, 14, 15, 160}}; + const GoalUUID uuid{{1, 20, 30, 4, 5, 6, 70, 8, 9, 1, 11, 120, 13, 14, 15, 160}}; auto handle_goal = []( - const GoalID &, std::shared_ptr) + const GoalUUID &, std::shared_ptr) { return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; }; @@ -550,10 +550,10 @@ TEST_F(TestServer, publish_feedback) TEST_F(TestServer, get_result) { auto node = std::make_shared("get_result", "/rclcpp_action/get_result"); - const GoalID uuid{{1, 2, 3, 4, 5, 6, 7, 80, 90, 10, 11, 12, 13, 14, 15, 160}}; + const GoalUUID uuid{{1, 2, 3, 4, 5, 6, 7, 80, 90, 10, 11, 12, 13, 14, 15, 160}}; auto handle_goal = []( - const GoalID &, std::shared_ptr) + const GoalUUID &, std::shared_ptr) { return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; }; @@ -586,7 +586,7 @@ TEST_F(TestServer, get_result) throw std::runtime_error("get result service didn't become available"); } auto request = std::make_shared(); - request->goal_id = uuid; + request->goal_id.uuid = uuid; auto future = result_client->async_send_request(request); // Send a result @@ -606,10 +606,10 @@ TEST_F(TestServer, get_result) TEST_F(TestServer, deferred_execution) { auto node = std::make_shared("defer_exec", "/rclcpp_action/defer_exec"); - const GoalID uuid{{1, 2, 3, 40, 5, 6, 70, 8, 9, 1, 11, 120, 13, 140, 15, 160}}; + const GoalUUID uuid{{1, 2, 3, 40, 5, 6, 70, 8, 9, 1, 11, 120, 13, 140, 15, 160}}; auto handle_goal = []( - const GoalID &, std::shared_ptr) + const GoalUUID &, std::shared_ptr) { return rclcpp_action::GoalResponse::ACCEPT_AND_DEFER; }; From 9e626fb8a51d74477ff9e1f2818819705a286bf5 Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Thu, 21 Feb 2019 15:04:40 -0800 Subject: [PATCH 05/10] remove obsolete comments --- rclcpp_action/include/rclcpp_action/client.hpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/rclcpp_action/include/rclcpp_action/client.hpp b/rclcpp_action/include/rclcpp_action/client.hpp index 1fd2aa024d..89db1e39f9 100644 --- a/rclcpp_action/include/rclcpp_action/client.hpp +++ b/rclcpp_action/include/rclcpp_action/client.hpp @@ -467,7 +467,6 @@ class Client : public ClientBase using GoalStatusMessage = typename ActionT::Impl::GoalStatusMessage; auto status_message = std::static_pointer_cast(message); for (const GoalStatus & status : status_message->status_list) { - // const GoalUUID & goal_id = status.goal_info.goal_id; const GoalUUID & goal_id = status.goal_info.goal_id.uuid; if (goal_handles_.count(goal_id) == 0) { RCLCPP_DEBUG( @@ -494,7 +493,6 @@ class Client : public ClientBase { using GoalResultRequest = typename ActionT::Impl::GetResultService::Request; auto goal_result_request = std::make_shared(); - // goal_result_request.goal_id = goal_handle->get_goal_id(); goal_result_request->goal_id.uuid = goal_handle->get_goal_id(); this->send_result_request( std::static_pointer_cast(goal_result_request), From 881501ba00a713e86dd703300132de530e1790b1 Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Tue, 26 Feb 2019 12:51:08 -0800 Subject: [PATCH 06/10] change signature of set_succeeded / set_canceled --- .../include/rclcpp_action/server_goal_handle.hpp | 16 ++++++++++------ rclcpp_action/test/test_server.cpp | 10 +++++----- 2 files changed, 15 insertions(+), 11 deletions(-) diff --git a/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp b/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp index 4257f89a53..d4b1888e82 100644 --- a/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp +++ b/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp @@ -179,11 +179,13 @@ class ServerGoalHandle : public ServerGoalHandleBase * \param[in] result_msg the final result to send to clients. */ void - set_succeeded(typename ActionT::Impl::GetResultService::Response::SharedPtr result_msg) + set_succeeded(typename ActionT::Result::SharedPtr result_msg) { _set_succeeded(); - result_msg->status = action_msgs::msg::GoalStatus::STATUS_SUCCEEDED; - on_terminal_state_(uuid_, result_msg); + auto response = std::make_shared(); + response->status = action_msgs::msg::GoalStatus::STATUS_SUCCEEDED; + response->result = *result_msg; + on_terminal_state_(uuid_, response); } /// Indicate that a goal has been canceled. @@ -196,11 +198,13 @@ class ServerGoalHandle : public ServerGoalHandleBase * \param[in] result_msg the final result to send to clients. */ void - set_canceled(typename ActionT::Impl::GetResultService::Response::SharedPtr result_msg) + set_canceled(typename ActionT::Result::SharedPtr result_msg) { _set_canceled(); - result_msg->status = action_msgs::msg::GoalStatus::STATUS_CANCELED; - on_terminal_state_(uuid_, result_msg); + auto response = std::make_shared(); + response->status = action_msgs::msg::GoalStatus::STATUS_CANCELED; + response->result = *result_msg; + on_terminal_state_(uuid_, response); } /// Indicate that the server is starting to execute a goal. diff --git a/rclcpp_action/test/test_server.cpp b/rclcpp_action/test/test_server.cpp index 8c94c82cda..76f2120fc3 100644 --- a/rclcpp_action/test/test_server.cpp +++ b/rclcpp_action/test/test_server.cpp @@ -364,7 +364,7 @@ TEST_F(TestServer, publish_status_canceled) send_goal_request(node, uuid); send_cancel_request(node, uuid); - received_handle->set_canceled(std::make_shared()); + received_handle->set_canceled(std::make_shared()); // 10 seconds const size_t max_tries = 10 * 1000 / 100; @@ -419,7 +419,7 @@ TEST_F(TestServer, publish_status_succeeded) }); send_goal_request(node, uuid); - received_handle->set_succeeded(std::make_shared()); + received_handle->set_succeeded(std::make_shared()); // 10 seconds const size_t max_tries = 10 * 1000 / 100; @@ -590,8 +590,8 @@ TEST_F(TestServer, get_result) auto future = result_client->async_send_request(request); // Send a result - auto result = std::make_shared(); - result->result.sequence = {5, 8, 13, 21}; + auto result = std::make_shared(); + result->sequence = {5, 8, 13, 21}; received_handle->set_succeeded(result); // Wait for the result request to be received @@ -600,7 +600,7 @@ TEST_F(TestServer, get_result) auto response = future.get(); EXPECT_EQ(action_msgs::msg::GoalStatus::STATUS_SUCCEEDED, response->status); - EXPECT_EQ(result->result.sequence, response->result.sequence); + EXPECT_EQ(result->sequence, response->result.sequence); } TEST_F(TestServer, deferred_execution) From 37f90954492478571b2e1aa0f5f51e3b394e7e0e Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Tue, 26 Feb 2019 13:06:33 -0800 Subject: [PATCH 07/10] change signature of on_terminal_state_(uuid_, result_msg);set_succeeded / set_canceled --- .../include/rclcpp_action/server_goal_handle.hpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp b/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp index d4b1888e82..5bff74d14c 100644 --- a/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp +++ b/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp @@ -162,11 +162,13 @@ class ServerGoalHandle : public ServerGoalHandleBase * \param[in] result_msg the final result to send to clients. */ void - set_aborted(typename ActionT::Impl::GetResultService::Response::SharedPtr result_msg) + set_aborted(typename ActionT::Result::SharedPtr result_msg) { _set_aborted(); - result_msg->status = action_msgs::msg::GoalStatus::STATUS_ABORTED; - on_terminal_state_(uuid_, result_msg); + auto response = std::make_shared(); + response->status = action_msgs::msg::GoalStatus::STATUS_ABORTED; + response->result = *result_msg; + on_terminal_state_(uuid_, response); } /// Indicate that a goal has been reached. From f81e86252f20c4a39950709bd11fb441bff07dee Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Tue, 26 Feb 2019 13:07:30 -0800 Subject: [PATCH 08/10] change signature of set_aborted --- rclcpp_action/test/test_server.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rclcpp_action/test/test_server.cpp b/rclcpp_action/test/test_server.cpp index 76f2120fc3..25e17d4ac6 100644 --- a/rclcpp_action/test/test_server.cpp +++ b/rclcpp_action/test/test_server.cpp @@ -474,7 +474,7 @@ TEST_F(TestServer, publish_status_aborted) }); send_goal_request(node, uuid); - received_handle->set_aborted(std::make_shared()); + received_handle->set_aborted(std::make_shared()); // 10 seconds const size_t max_tries = 10 * 1000 / 100; From d1e8c9ca0f3640ea92c9244817c2cf7280fa1c22 Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Tue, 26 Feb 2019 13:17:11 -0800 Subject: [PATCH 09/10] change signature of publish_feedback --- .../include/rclcpp_action/server_goal_handle.hpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp b/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp index 5bff74d14c..0534d933f5 100644 --- a/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp +++ b/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp @@ -145,10 +145,12 @@ class ServerGoalHandle : public ServerGoalHandleBase * \param[in] feedback_msg the message to publish to clients. */ void - publish_feedback(std::shared_ptr feedback_msg) + publish_feedback(std::shared_ptr feedback_msg) { - feedback_msg->goal_id.uuid = uuid_; - publish_feedback_(feedback_msg); + auto feedback_message = std::make_shared(); + feedback_message->goal_id.uuid = uuid_; + feedback_message->feedback = *feedback_msg; + publish_feedback_(feedback_message); } // TODO(sloretz) which exception is raised? From 0026e2559c74ed8866df015cbc2cd38deb9f359e Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Tue, 26 Feb 2019 15:19:42 -0800 Subject: [PATCH 10/10] update another test --- rclcpp_action/test/test_server.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/rclcpp_action/test/test_server.cpp b/rclcpp_action/test/test_server.cpp index 25e17d4ac6..304bbdda30 100644 --- a/rclcpp_action/test/test_server.cpp +++ b/rclcpp_action/test/test_server.cpp @@ -531,8 +531,8 @@ TEST_F(TestServer, publish_feedback) send_goal_request(node, uuid); - auto sent_message = std::make_shared(); - sent_message->feedback.sequence = {1, 1, 2, 3, 5}; + auto sent_message = std::make_shared(); + sent_message->sequence = {1, 1, 2, 3, 5}; received_handle->publish_feedback(sent_message); // 10 seconds @@ -544,7 +544,7 @@ TEST_F(TestServer, publish_feedback) ASSERT_EQ(1u, received_msgs.size()); auto & msg = received_msgs.back(); - ASSERT_EQ(sent_message->feedback.sequence, msg->feedback.sequence); + ASSERT_EQ(sent_message->sequence, msg->feedback.sequence); } TEST_F(TestServer, get_result)