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 c709e0331a..658f8babc6 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 @@ -53,17 +52,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() @@ -88,9 +87,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); @@ -106,29 +105,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(); } @@ -137,11 +137,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); @@ -170,11 +170,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)