update to use separated action types (#601)

* match renamed action types

* fix action type casting

* rename type/field to use correct term

* rename custom GoalID type to avoid naming collision, update types using unique_identifier_msgs

* remove obsolete comments

* change signature of set_succeeded / set_canceled

* change signature of     on_terminal_state_(uuid_, result_msg);set_succeeded / set_canceled

* change signature of set_aborted

* change signature of publish_feedback

* update another test
This commit is contained in:
Michel Hidalgo 2019-03-11 21:12:47 -07:00 committed by Dirk Thomas
parent d2d9ad8796
commit 718d24f942
11 changed files with 220 additions and 219 deletions

View file

@ -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
{
@ -36,16 +36,16 @@ protected:
rclcpp::init(0, nullptr);
}
std::shared_ptr<Fibonacci::GoalRequestService::Request>
send_goal_request(rclcpp::Node::SharedPtr node, GoalID uuid)
std::shared_ptr<Fibonacci::Impl::SendGoalService::Request>
send_goal_request(rclcpp::Node::SharedPtr node, GoalUUID uuid)
{
auto client = node->create_client<Fibonacci::GoalRequestService>(
auto client = node->create_client<Fibonacci::Impl::SendGoalService>(
"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<Fibonacci::GoalRequestService::Request>();
request->action_goal_id.uuid = uuid;
auto request = std::make_shared<Fibonacci::Impl::SendGoalService::Request>();
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,14 +56,14 @@ protected:
}
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::CancelGoalService>(
auto cancel_client = node->create_client<Fibonacci::Impl::CancelGoalService>(
"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<Fibonacci::CancelGoalService::Request>();
auto request = std::make_shared<Fibonacci::Impl::CancelGoalService::Request>();
request->goal_info.goal_id.uuid = uuid;
auto future = cancel_client->async_send_request(request);
if (rclcpp::executor::FutureReturnCode::SUCCESS !=
@ -80,7 +80,7 @@ TEST_F(TestServer, construction_and_destruction)
using GoalHandle = rclcpp_action::ServerGoalHandle<Fibonacci>;
auto as = rclcpp_action::create_server<Fibonacci>(node, "fibonacci",
[](const GoalID &, std::shared_ptr<const Fibonacci::Goal>) {
[](const GoalUUID &, std::shared_ptr<const Fibonacci::Goal>) {
return rclcpp_action::GoalResponse::REJECT;
},
[](std::shared_ptr<GoalHandle>) {
@ -93,10 +93,10 @@ TEST_F(TestServer, construction_and_destruction)
TEST_F(TestServer, handle_goal_called)
{
auto node = std::make_shared<rclcpp::Node>("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 Fibonacci::Goal>)
const GoalUUID & uuid, std::shared_ptr<const Fibonacci::Goal>)
{
received_uuid = uuid;
return rclcpp_action::GoalResponse::REJECT;
@ -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<Fibonacci::GoalRequestService>(
auto client = node->create_client<Fibonacci::Impl::SendGoalService>(
"fibonacci/_action/send_goal");
ASSERT_TRUE(client->wait_for_service(std::chrono::seconds(20)));
auto request = std::make_shared<Fibonacci::GoalRequestService::Request>();
auto request = std::make_shared<Fibonacci::Impl::SendGoalService::Request>();
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;
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<rclcpp::Node>("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 Fibonacci::Goal>)
const GoalUUID &, std::shared_ptr<const Fibonacci::Goal>)
{
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
};
@ -164,16 +164,16 @@ 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)
{
auto node = std::make_shared<rclcpp::Node>("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 Fibonacci::Goal>)
const GoalUUID &, std::shared_ptr<const Fibonacci::Goal>)
{
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<rclcpp::Node>("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 Fibonacci::Goal>)
const GoalUUID &, std::shared_ptr<const Fibonacci::Goal>)
{
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<rclcpp::Node>("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 Fibonacci::Goal>)
const GoalUUID &, std::shared_ptr<const Fibonacci::Goal>)
{
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<rclcpp::Node>("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 Fibonacci::Goal>)
const GoalUUID &, std::shared_ptr<const Fibonacci::Goal>)
{
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<rclcpp::Node>("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 Fibonacci::Goal>)
const GoalUUID &, std::shared_ptr<const Fibonacci::Goal>)
{
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<rclcpp::Node>("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 Fibonacci::Goal>)
const GoalUUID &, std::shared_ptr<const Fibonacci::Goal>)
{
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<rclcpp::Node>("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 Fibonacci::Goal>)
const GoalUUID &, std::shared_ptr<const Fibonacci::Goal>)
{
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
};
@ -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<FeedbackT::SharedPtr> received_msgs;
auto subscriber = node->create_subscription<FeedbackT>(
"fibonacci/_action/feedback", [&received_msgs](FeedbackT::SharedPtr msg)
@ -531,7 +531,7 @@ TEST_F(TestServer, publish_feedback)
send_goal_request(node, uuid);
auto sent_message = std::make_shared<FeedbackT>();
auto sent_message = std::make_shared<Fibonacci::Feedback>();
sent_message->sequence = {1, 1, 2, 3, 5};
received_handle->publish_feedback(sent_message);
@ -544,17 +544,16 @@ 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->sequence, msg->feedback.sequence);
}
TEST_F(TestServer, get_result)
{
auto node = std::make_shared<rclcpp::Node>("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 Fibonacci::Goal>)
const GoalUUID &, std::shared_ptr<const Fibonacci::Goal>)
{
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
};
@ -581,13 +580,13 @@ TEST_F(TestServer, get_result)
send_goal_request(node, uuid);
// Send result request
auto result_client = node->create_client<Fibonacci::GoalResultService>(
auto result_client = node->create_client<Fibonacci::Impl::GetResultService>(
"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<Fibonacci::GoalResultService::Request>();
request->action_goal_id.uuid = uuid;
auto request = std::make_shared<Fibonacci::Impl::GetResultService::Request>();
request->goal_id.uuid = uuid;
auto future = result_client->async_send_request(request);
// Send a result
@ -600,17 +599,17 @@ 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->sequence, response->result.sequence);
}
TEST_F(TestServer, deferred_execution)
{
auto node = std::make_shared<rclcpp::Node>("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 Fibonacci::Goal>)
const GoalUUID &, std::shared_ptr<const Fibonacci::Goal>)
{
return rclcpp_action::GoalResponse::ACCEPT_AND_DEFER;
};