Skip to content

Commit

Permalink
Change callback parameter from C type to C++
Browse files Browse the repository at this point in the history
  • Loading branch information
sloretz committed Nov 30, 2018
1 parent 9470e8a commit c9faf25
Show file tree
Hide file tree
Showing 4 changed files with 34 additions and 22 deletions.
14 changes: 14 additions & 0 deletions rclcpp_action/include/rclcpp_action/create_server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,5 +52,19 @@ create_server(
node->get_node_waitables_interface()->add_waitable(action_server, nullptr);
return action_server;
}

template<typename ACTION>
typename Server<ACTION>::SharedPtr
create_server(
rclcpp::Node::SharedPtr node,
const std::string & name,
typename Server<ACTION>::GoalCallback handle_goal,
typename Server<ACTION>::CancelCallback handle_cancel,
typename Server<ACTION>::ExecuteCallback handle_execute,
const rcl_action_server_options_t & options = rcl_action_server_get_default_options())
{
return create_server<ACTION>(
node.get(), name, handle_goal, handle_cancel, handle_execute, options);
}
} // namespace rclcpp_action
#endif // RCLCPP_ACTION__CREATE_SERVER_HPP_
8 changes: 4 additions & 4 deletions rclcpp_action/include/rclcpp_action/server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ class ServerBase : public rclcpp::Waitable
RCLCPP_ACTION_PUBLIC
virtual
std::pair<GoalResponse, std::shared_ptr<void>>
call_handle_goal_callback(rcl_action_goal_info_t &, std::shared_ptr<void> request) = 0;
call_handle_goal_callback(std::array<uint8_t, 16> &, std::shared_ptr<void> request) = 0;

// ServerBase will determine which goal ids are being cancelled, and then call this function for
// each goal id.
Expand Down Expand Up @@ -213,7 +213,7 @@ class Server : public ServerBase
RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(Server)

using GoalCallback = std::function<GoalResponse(
rcl_action_goal_info_t &, std::shared_ptr<typename ACTION::Goal>)>;
std::array<uint8_t, 16>&, std::shared_ptr<typename ACTION::Goal>)>;
using CancelCallback = std::function<CancelResponse(std::shared_ptr<ServerGoalHandle<ACTION>>)>;
using ExecuteCallback = std::function<void (std::shared_ptr<ServerGoalHandle<ACTION>>)>;

Expand Down Expand Up @@ -244,14 +244,14 @@ class Server : public ServerBase

protected:
std::pair<GoalResponse, std::shared_ptr<void>>
call_handle_goal_callback(rcl_action_goal_info_t & info, std::shared_ptr<void> message) override
call_handle_goal_callback(std::array<uint8_t, 16> & uuid, std::shared_ptr<void> message) override
{
// TODO(sloretz) update and remove assert when IDL pipeline allows nesting user's type
static_assert(
std::is_same<typename ACTION::Goal, typename ACTION::GoalRequestService::Request>::value,
"Assuming user fields were merged with goal request fields");
GoalResponse user_response = handle_goal_(
info, std::static_pointer_cast<typename ACTION::Goal>(message));
uuid, std::static_pointer_cast<typename ACTION::Goal>(message));

auto ros_response = std::make_shared<typename ACTION::GoalRequestService::Response>();
ros_response->accepted = GoalResponse::ACCEPT == user_response;
Expand Down
2 changes: 1 addition & 1 deletion rclcpp_action/src/server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -208,7 +208,7 @@ ServerBase::execute_goal_request_received()
}

// Call user's callback, getting the user's response and a ros message to send back
auto response_pair = call_handle_goal_callback(goal_info, message);
auto response_pair = call_handle_goal_callback(uuid, message);

ret = rcl_action_send_goal_response(
pimpl_->action_server_.get(),
Expand Down
32 changes: 15 additions & 17 deletions rclcpp_action/test/test_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ TEST_F(TestServer, construction_and_destruction)

using GoalHandle = rclcpp_action::ServerGoalHandle<test_msgs::action::Fibonacci>;
auto as = rclcpp_action::create_server<test_msgs::action::Fibonacci>(node.get(), "fibonacci",
[](rcl_action_goal_info_t &, std::shared_ptr<test_msgs::action::Fibonacci::Goal>) {
[](std::array<uint8_t, 16> &, std::shared_ptr<test_msgs::action::Fibonacci::Goal>) {
return rclcpp_action::GoalResponse::REJECT;
},
[](std::shared_ptr<GoalHandle>) {
Expand All @@ -91,12 +91,12 @@ 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");
rcl_action_goal_info_t received_info;
std::array<uint8_t, 16> received_uuid;

auto handle_goal = [&received_info](
rcl_action_goal_info_t & info, std::shared_ptr<test_msgs::action::Fibonacci::Goal>)
auto handle_goal = [&received_uuid](
std::array<uint8_t, 16> & uuid, std::shared_ptr<test_msgs::action::Fibonacci::Goal>)
{
received_info = info;
received_uuid = uuid;
return rclcpp_action::GoalResponse::REJECT;
};

Expand Down Expand Up @@ -127,9 +127,7 @@ TEST_F(TestServer, handle_goal_called)
rclcpp::executor::FutureReturnCode::SUCCESS,
rclcpp::spin_until_future_complete(node, future));

for (size_t i = 0; i < 16; ++i) {
EXPECT_EQ(uuid[i], received_info.uuid[i]) << "at idx " << i;
}
ASSERT_EQ(uuid, received_uuid);
}

TEST_F(TestServer, handle_execute_called)
Expand All @@ -138,7 +136,7 @@ TEST_F(TestServer, handle_execute_called)
const std::array<uint8_t, 16> uuid{{1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16}};

auto handle_goal = [](
rcl_action_goal_info_t &, std::shared_ptr<test_msgs::action::Fibonacci::Goal>)
std::array<uint8_t, 16> &, std::shared_ptr<test_msgs::action::Fibonacci::Goal>)
{
return rclcpp_action::GoalResponse::ACCEPT;
};
Expand Down Expand Up @@ -173,7 +171,7 @@ TEST_F(TestServer, handle_cancel_called)
const std::array<uint8_t, 16> uuid{{10, 20, 30, 40, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16}};

auto handle_goal = [](
rcl_action_goal_info_t &, std::shared_ptr<test_msgs::action::Fibonacci::Goal>)
std::array<uint8_t, 16> &, std::shared_ptr<test_msgs::action::Fibonacci::Goal>)
{
return rclcpp_action::GoalResponse::ACCEPT;
};
Expand Down Expand Up @@ -213,7 +211,7 @@ TEST_F(TestServer, publish_status_accepted)
const std::array<uint8_t, 16> uuid{{1, 2, 3, 4, 5, 6, 7, 8, 9, 100, 110, 120, 13, 14, 15, 16}};

auto handle_goal = [](
rcl_action_goal_info_t &, std::shared_ptr<test_msgs::action::Fibonacci::Goal>)
std::array<uint8_t, 16> &, std::shared_ptr<test_msgs::action::Fibonacci::Goal>)
{
return rclcpp_action::GoalResponse::ACCEPT;
};
Expand Down Expand Up @@ -274,7 +272,7 @@ TEST_F(TestServer, publish_status_canceling)
const std::array<uint8_t, 16> uuid{{1, 2, 3, 40, 5, 6, 7, 80, 9, 10, 11, 120, 13, 14, 15, 160}};

auto handle_goal = [](
rcl_action_goal_info_t &, std::shared_ptr<test_msgs::action::Fibonacci::Goal>)
std::array<uint8_t, 16> &, std::shared_ptr<test_msgs::action::Fibonacci::Goal>)
{
return rclcpp_action::GoalResponse::ACCEPT;
};
Expand Down Expand Up @@ -329,7 +327,7 @@ TEST_F(TestServer, publish_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}};

auto handle_goal = [](
rcl_action_goal_info_t &, std::shared_ptr<test_msgs::action::Fibonacci::Goal>)
std::array<uint8_t, 16> &, std::shared_ptr<test_msgs::action::Fibonacci::Goal>)
{
return rclcpp_action::GoalResponse::ACCEPT;
};
Expand Down Expand Up @@ -386,7 +384,7 @@ TEST_F(TestServer, publish_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}};

auto handle_goal = [](
rcl_action_goal_info_t &, std::shared_ptr<test_msgs::action::Fibonacci::Goal>)
std::array<uint8_t, 16> &, std::shared_ptr<test_msgs::action::Fibonacci::Goal>)
{
return rclcpp_action::GoalResponse::ACCEPT;
};
Expand Down Expand Up @@ -441,7 +439,7 @@ TEST_F(TestServer, publish_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}};

auto handle_goal = [](
rcl_action_goal_info_t &, std::shared_ptr<test_msgs::action::Fibonacci::Goal>)
std::array<uint8_t, 16> &, std::shared_ptr<test_msgs::action::Fibonacci::Goal>)
{
return rclcpp_action::GoalResponse::ACCEPT;
};
Expand Down Expand Up @@ -496,7 +494,7 @@ TEST_F(TestServer, publish_feedback)
const std::array<uint8_t, 16> uuid{{1, 20, 30, 4, 5, 6, 70, 8, 9, 1, 11, 120, 13, 14, 15, 160}};

auto handle_goal = [](
rcl_action_goal_info_t &, std::shared_ptr<test_msgs::action::Fibonacci::Goal>)
std::array<uint8_t, 16> &, std::shared_ptr<test_msgs::action::Fibonacci::Goal>)
{
return rclcpp_action::GoalResponse::ACCEPT;
};
Expand Down Expand Up @@ -553,7 +551,7 @@ TEST_F(TestServer, 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}};

auto handle_goal = [](
rcl_action_goal_info_t &, std::shared_ptr<test_msgs::action::Fibonacci::Goal>)
std::array<uint8_t, 16> &, std::shared_ptr<test_msgs::action::Fibonacci::Goal>)
{
return rclcpp_action::GoalResponse::ACCEPT;
};
Expand Down

0 comments on commit c9faf25

Please sign in to comment.