Skip to content

Commit

Permalink
Adapts action client to new action type support layout.
Browse files Browse the repository at this point in the history
  • Loading branch information
hidmic committed Dec 6, 2018
1 parent 9116739 commit e369979
Show file tree
Hide file tree
Showing 3 changed files with 27 additions and 28 deletions.
32 changes: 15 additions & 17 deletions rclcpp_action/include/rclcpp_action/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -261,11 +261,10 @@ class Client : public ClientBase
auto promise = std::make_shared<std::promise<typename GoalHandle::SharedPtr>>();
std::shared_future<typename GoalHandle::SharedPtr> future(promise->get_future());
using GoalRequest = typename ActionT::GoalRequestService::Request;
// auto goal_request = std::make_shared<GoalRequest>();
// goal_request->goal_id = this->generate_goal_id();
// goal_request->goal = goal;
auto goal_request = std::make_shared<GoalRequest>(goal);
auto goal_request = std::make_shared<GoalRequest>();
goal_request->uuid = this->generate_goal_id();
goal_request->request = goal;
this->send_goal_request(
std::static_pointer_cast<void>(goal_request),
[this, goal_request, callback, ignore_result, promise](
Expand Down Expand Up @@ -403,22 +402,18 @@ class Client : public ClientBase
std::shared_ptr<void>
create_feedback_message() const override
{
// using FeedbackMessage = typename ActionT::FeedbackMessage;
// return std::shared_ptr<void>(new FeedbackMessage());
return std::shared_ptr<void>(new Feedback());
using FeedbackMessage = typename ActionT::FeedbackMessage;
return std::shared_ptr<void>(new FeedbackMessage());
}

/// \internal
void
handle_feedback_message(std::shared_ptr<void> message) override
{
std::lock_guard<std::mutex> guard(goal_handles_mutex_);
// using FeedbackMessage = typename ActionT::FeedbackMessage;
// typename FeedbackMessage::SharedPtr feedback_message =
// std::static_pointer_cast<FeedbackMessage>(message);
typename Feedback::SharedPtr feedback_message =
std::static_pointer_cast<Feedback>(message);
// const GoalID & goal_id = feedback_message->goal_id;
using FeedbackMessage = typename ActionT::FeedbackMessage;
typename FeedbackMessage::SharedPtr feedback_message =
std::static_pointer_cast<FeedbackMessage>(message);
const GoalID & goal_id = feedback_message->uuid;
if (goal_handles_.count(goal_id) == 0) {
RCLCPP_DEBUG(
Expand All @@ -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 = feedback_message->feedback;
goal_handle->call_feedback_callback(goal_handle, feedback);
}

/// \internal
Expand Down Expand Up @@ -480,12 +476,14 @@ class Client : public ClientBase
std::static_pointer_cast<void>(goal_result_request),
[goal_handle, this](std::shared_ptr<void> response) mutable
{
using GoalResultResponse = typename ActionT::GoalResultService::Response;
auto result_response = std::static_pointer_cast<GoalResultResponse>(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<GoalResultResponse>(response);
result.response = std::make_shared<typename ActionT::Result>();
*result.response = result_response->response;
result.goal_id = goal_handle->get_goal_id();
result.code = static_cast<ResultCode>(result.response->status);
result.code = static_cast<ResultCode>(result_response->status);
goal_handle->set_result(result);
std::lock_guard<std::mutex> lock(goal_handles_mutex_);
goal_handles_.erase(goal_handle->get_goal_id());
Expand Down
3 changes: 2 additions & 1 deletion rclcpp_action/include/rclcpp_action/client_goal_handle.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,8 @@ class ClientGoalHandle
using Feedback = typename ActionT::Feedback;
using FeedbackCallback =
std::function<void (
typename ClientGoalHandle<ActionT>::SharedPtr, const std::shared_ptr<const Feedback>)>;
typename ClientGoalHandle<ActionT>::SharedPtr,
const std::shared_ptr<const Feedback>)>;

virtual ~ClientGoalHandle();

Expand Down
20 changes: 10 additions & 10 deletions rclcpp_action/test/test_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,6 @@
#include <rclcpp/clock.hpp>
#include <rclcpp/exceptions.hpp>
#include <rclcpp/executors.hpp>
#include <rclcpp/executors/multi_threaded_executor.hpp>
#include <rclcpp/node.hpp>
#include <rclcpp/publisher.hpp>
#include <rclcpp/rclcpp.hpp>
Expand Down Expand Up @@ -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()
Expand All @@ -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};
}
Expand Down Expand Up @@ -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();
}
Expand All @@ -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 {
Expand Down

0 comments on commit e369979

Please sign in to comment.