diff --git a/rclcpp_action/include/rclcpp_action/client.hpp b/rclcpp_action/include/rclcpp_action/client.hpp index 0ce4b4a948..1751fe8c15 100644 --- a/rclcpp_action/include/rclcpp_action/client.hpp +++ b/rclcpp_action/include/rclcpp_action/client.hpp @@ -287,7 +287,6 @@ 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); @@ -429,9 +428,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 @@ -453,8 +451,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 @@ -506,10 +505,12 @@ 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->action_status); goal_handle->set_result(result); 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 c709e0331a..5cf3f7d1c4 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->action_goal_id.uuid] = {request, response}; } @@ -122,13 +121,14 @@ class TestClient : public ::testing::Test feedback_message.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(); }