diff --git a/rclcpp_action/include/rclcpp_action/client.hpp b/rclcpp_action/include/rclcpp_action/client.hpp index 531f705d75..062d45d385 100644 --- a/rclcpp_action/include/rclcpp_action/client.hpp +++ b/rclcpp_action/include/rclcpp_action/client.hpp @@ -261,11 +261,10 @@ class Client : public ClientBase 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); + auto goal_request = std::make_shared(); goal_request->uuid = this->generate_goal_id(); + goal_request->request = goal; this->send_goal_request( std::static_pointer_cast(goal_request), [this, goal_request, callback, ignore_result, promise]( @@ -403,9 +402,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::FeedbackMessage; + return std::shared_ptr(new FeedbackMessage()); } /// \internal @@ -413,12 +411,9 @@ 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; + using FeedbackMessage = typename ActionT::FeedbackMessage; + typename FeedbackMessage::SharedPtr feedback_message = + std::static_pointer_cast(message); const GoalID & goal_id = feedback_message->uuid; if (goal_handles_.count(goal_id) == 0) { RCLCPP_DEBUG( @@ -427,8 +422,9 @@ 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 @@ -480,12 +476,14 @@ class Client : public ClientBase std::static_pointer_cast(goal_result_request), [goal_handle, this](std::shared_ptr response) mutable { + using GoalResultResponse = typename ActionT::GoalResultService::Response; + auto result_response = std::static_pointer_cast(response); // 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); + result.response = std::make_shared(); + *result.response = result_response->response; result.goal_id = goal_handle->get_goal_id(); - result.code = static_cast(result.response->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/test/test_client.cpp b/rclcpp_action/test/test_client.cpp index 22c3020452..d079fac5e3 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 @@ -63,7 +62,7 @@ class TestClient : public ::testing::Test using ActionCancelGoalRequest = ActionType::CancelGoalService::Request; using ActionCancelGoalResponse = ActionType::CancelGoalService::Response; using ActionStatusMessage = ActionType::GoalStatusMessage; - using ActionFeedbackMessage = ActionType::Feedback; + using ActionFeedbackMessage = ActionType::FeedbackMessage; using ActionFeedback = ActionType::Feedback; static void SetUpTestCase() @@ -88,7 +87,7 @@ class TestClient : public ::testing::Test ActionGoalResponse::SharedPtr response) { response->stamp = clock.now(); - response->accepted = (request->order >= 0); + response->accepted = (request->request.order >= 0); if (response->accepted) { goals[request->uuid] = {request, response}; } @@ -119,16 +118,17 @@ class TestClient : public ::testing::Test client_executor.spin_once(); ActionFeedbackMessage feedback_message; feedback_message.uuid = goal_request->uuid; - feedback_message.sequence.push_back(0); + 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->request.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->request.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,7 +137,7 @@ 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->response.sequence = feedback_message.feedback.sequence; response->status = rclcpp_action::GoalStatus::STATUS_SUCCEEDED; goals.erase(request->uuid); } else {