Skip to content

Commit

Permalink
Array -> GoalID
Browse files Browse the repository at this point in the history
  • Loading branch information
sloretz committed Dec 6, 2018
1 parent 039854d commit 71c7100
Showing 1 changed file with 27 additions and 26 deletions.
53 changes: 27 additions & 26 deletions rclcpp_action/test/test_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
#include "rclcpp_action/server.hpp"

using Fibonacci = test_msgs::action::Fibonacci;
using GoalID = rclcpp_action::GoalID;

class TestServer : public ::testing::Test
{
Expand All @@ -36,7 +37,7 @@ class TestServer : public ::testing::Test
}

std::shared_ptr<Fibonacci::GoalRequestService::Request>
send_goal_request(rclcpp::Node::SharedPtr node, std::array<uint8_t, 16> uuid)
send_goal_request(rclcpp::Node::SharedPtr node, GoalID uuid)
{
auto client = node->create_client<Fibonacci::GoalRequestService>(
"fibonacci/_action/send_goal");
Expand All @@ -55,7 +56,7 @@ class TestServer : public ::testing::Test
}

void
send_cancel_request(rclcpp::Node::SharedPtr node, std::array<uint8_t, 16> uuid)
send_cancel_request(rclcpp::Node::SharedPtr node, GoalID uuid)
{
auto cancel_client = node->create_client<Fibonacci::CancelGoalService>(
"fibonacci/_action/cancel_goal");
Expand All @@ -79,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 std::array<uint8_t, 16> &, std::shared_ptr<const Fibonacci::Goal>) {
[](const GoalID &, std::shared_ptr<const Fibonacci::Goal>) {
return rclcpp_action::GoalResponse::REJECT;
},
[](std::shared_ptr<GoalHandle>) {
Expand All @@ -92,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");
std::array<uint8_t, 16> received_uuid;
GoalID received_uuid;

auto handle_goal = [&received_uuid](
const std::array<uint8_t, 16> & uuid, std::shared_ptr<const Fibonacci::Goal>)
const GoalID & uuid, std::shared_ptr<const Fibonacci::Goal>)
{
received_uuid = uuid;
return rclcpp_action::GoalResponse::REJECT;
Expand All @@ -120,7 +121,7 @@ TEST_F(TestServer, handle_goal_called)

auto request = std::make_shared<Fibonacci::GoalRequestService::Request>();

const std::array<uint8_t, 16> uuid{{1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16}};
const GoalID uuid{{1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16}};
request->uuid = uuid;

auto future = client->async_send_request(request);
Expand All @@ -134,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 std::array<uint8_t, 16> uuid{{1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16}};
const GoalID uuid{{1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16}};

auto handle_goal = [](
const std::array<uint8_t, 16> &, std::shared_ptr<const Fibonacci::Goal>)
const GoalID &, std::shared_ptr<const Fibonacci::Goal>)
{
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
};
Expand Down Expand Up @@ -169,10 +170,10 @@ TEST_F(TestServer, handle_accepted_called)
TEST_F(TestServer, handle_cancel_called)
{
auto node = std::make_shared<rclcpp::Node>("handle_cancel_node", "/rclcpp_action/handle_cancel");
const std::array<uint8_t, 16> uuid{{10, 20, 30, 40, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16}};
const GoalID uuid{{10, 20, 30, 40, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16}};

auto handle_goal = [](
const std::array<uint8_t, 16> &, std::shared_ptr<const Fibonacci::Goal>)
const GoalID &, std::shared_ptr<const Fibonacci::Goal>)
{
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
};
Expand Down Expand Up @@ -209,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 std::array<uint8_t, 16> uuid{{1, 2, 3, 4, 5, 6, 7, 8, 9, 100, 110, 120, 13, 14, 15, 16}};
const GoalID uuid{{1, 2, 3, 4, 5, 6, 7, 8, 9, 100, 110, 120, 13, 14, 15, 16}};

auto handle_goal = [](
const std::array<uint8_t, 16> &, std::shared_ptr<const Fibonacci::Goal>)
const GoalID &, std::shared_ptr<const Fibonacci::Goal>)
{
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
};
Expand Down Expand Up @@ -270,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 std::array<uint8_t, 16> uuid{{1, 2, 3, 40, 5, 6, 7, 80, 9, 10, 11, 120, 13, 14, 15, 160}};
const GoalID uuid{{1, 2, 3, 40, 5, 6, 7, 80, 9, 10, 11, 120, 13, 14, 15, 160}};

auto handle_goal = [](
const std::array<uint8_t, 16> &, std::shared_ptr<const Fibonacci::Goal>)
const GoalID &, std::shared_ptr<const Fibonacci::Goal>)
{
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
};
Expand Down Expand Up @@ -325,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 std::array<uint8_t, 16> uuid{{1, 2, 3, 40, 5, 6, 70, 8, 9, 1, 11, 120, 13, 140, 15, 160}};
const GoalID uuid{{1, 2, 3, 40, 5, 6, 70, 8, 9, 1, 11, 120, 13, 140, 15, 160}};

auto handle_goal = [](
const std::array<uint8_t, 16> &, std::shared_ptr<const Fibonacci::Goal>)
const GoalID &, std::shared_ptr<const Fibonacci::Goal>)
{
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
};
Expand Down Expand Up @@ -382,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 std::array<uint8_t, 16> uuid{{1, 2, 3, 40, 5, 6, 70, 8, 9, 1, 11, 120, 13, 140, 15, 160}};
const GoalID uuid{{1, 2, 3, 40, 5, 6, 70, 8, 9, 1, 11, 120, 13, 140, 15, 160}};

auto handle_goal = [](
const std::array<uint8_t, 16> &, std::shared_ptr<const Fibonacci::Goal>)
const GoalID &, std::shared_ptr<const Fibonacci::Goal>)
{
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
};
Expand Down Expand Up @@ -437,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 std::array<uint8_t, 16> uuid{{1, 2, 3, 40, 5, 6, 70, 8, 9, 1, 11, 120, 13, 140, 15, 160}};
const GoalID uuid{{1, 2, 3, 40, 5, 6, 70, 8, 9, 1, 11, 120, 13, 140, 15, 160}};

auto handle_goal = [](
const std::array<uint8_t, 16> &, std::shared_ptr<const Fibonacci::Goal>)
const GoalID &, std::shared_ptr<const Fibonacci::Goal>)
{
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
};
Expand Down Expand Up @@ -492,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 std::array<uint8_t, 16> uuid{{1, 20, 30, 4, 5, 6, 70, 8, 9, 1, 11, 120, 13, 14, 15, 160}};
const GoalID uuid{{1, 20, 30, 4, 5, 6, 70, 8, 9, 1, 11, 120, 13, 14, 15, 160}};

auto handle_goal = [](
const std::array<uint8_t, 16> &, std::shared_ptr<const Fibonacci::Goal>)
const GoalID &, std::shared_ptr<const Fibonacci::Goal>)
{
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
};
Expand Down Expand Up @@ -550,10 +551,10 @@ TEST_F(TestServer, publish_feedback)
TEST_F(TestServer, get_result)
{
auto node = std::make_shared<rclcpp::Node>("get_result", "/rclcpp_action/get_result");
const std::array<uint8_t, 16> uuid{{1, 2, 3, 4, 5, 6, 7, 80, 90, 10, 11, 12, 13, 14, 15, 160}};
const GoalID uuid{{1, 2, 3, 4, 5, 6, 7, 80, 90, 10, 11, 12, 13, 14, 15, 160}};

auto handle_goal = [](
const std::array<uint8_t, 16> &, std::shared_ptr<const Fibonacci::Goal>)
const GoalID &, std::shared_ptr<const Fibonacci::Goal>)
{
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
};
Expand Down Expand Up @@ -606,10 +607,10 @@ TEST_F(TestServer, get_result)
TEST_F(TestServer, deferred_execution)
{
auto node = std::make_shared<rclcpp::Node>("defer_exec", "/rclcpp_action/defer_exec");
const std::array<uint8_t, 16> uuid{{1, 2, 3, 40, 5, 6, 70, 8, 9, 1, 11, 120, 13, 140, 15, 160}};
const GoalID uuid{{1, 2, 3, 40, 5, 6, 70, 8, 9, 1, 11, 120, 13, 140, 15, 160}};

auto handle_goal = [](
const std::array<uint8_t, 16> &, std::shared_ptr<const Fibonacci::Goal>)
const GoalID &, std::shared_ptr<const Fibonacci::Goal>)
{
return rclcpp_action::GoalResponse::ACCEPT_AND_DEFER;
};
Expand Down

0 comments on commit 71c7100

Please sign in to comment.