Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

overload for node interfaces #700

Merged
merged 3 commits into from
Apr 17, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
46 changes: 39 additions & 7 deletions rclcpp_action/include/rclcpp_action/create_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,20 +27,29 @@ namespace rclcpp_action
{
/// Create an action client.
/**
* \param[in] node The action client will be added to this node.
* This function is equivalent to \sa create_client()` however is using the individual
* node interfaces to create the client.
*
* \param node_base_interface[in] The node base interface of the corresponding node.
* \param node_graph_interface[in] The node graph interface of the corresponding node.
* \param node_logging_interface[in] The node logging interface of the corresponding node.
* \param node_waitables_interface[in] The node waitables interface of the corresponding node.
* \param[in] name The action name.
* \param[in] group The action client will be added to this callback group.
* If `nullptr`, then the action client is added to the default callback group.
*/
template<typename ActionT>
typename Client<ActionT>::SharedPtr
create_client(
rclcpp::Node::SharedPtr node,
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface,
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface,
const std::string & name,
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr)
{
std::weak_ptr<rclcpp::node_interfaces::NodeWaitablesInterface> weak_node =
node->get_node_waitables_interface();
node_waitables_interface;
std::weak_ptr<rclcpp::callback_group::CallbackGroup> weak_group = group;
bool group_is_null = (nullptr == group.get());

Expand Down Expand Up @@ -71,15 +80,38 @@ create_client(

std::shared_ptr<Client<ActionT>> action_client(
new Client<ActionT>(
node->get_node_base_interface(),
node->get_node_graph_interface(),
node->get_node_logging_interface(),
node_base_interface,
node_graph_interface,
node_logging_interface,
name),
deleter);

node->get_node_waitables_interface()->add_waitable(action_client, group);
node_waitables_interface->add_waitable(action_client, group);
return action_client;
}

/// Create an action client.
/**
* \param[in] node The action client will be added to this node.
* \param[in] name The action name.
* \param[in] group The action client will be added to this callback group.
* If `nullptr`, then the action client is added to the default callback group.
*/
template<typename ActionT>
typename Client<ActionT>::SharedPtr
create_client(
rclcpp::Node::SharedPtr node,
const std::string & name,
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr)
{
return create_client<ActionT>(
node->get_node_base_interface(),
node->get_node_graph_interface(),
node->get_node_logging_interface(),
node->get_node_waitables_interface(),
name,
group);
}
} // namespace rclcpp_action

#endif // RCLCPP_ACTION__CREATE_CLIENT_HPP_
63 changes: 56 additions & 7 deletions rclcpp_action/include/rclcpp_action/create_server.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,10 +34,15 @@ namespace rclcpp_action
/// Create an action server.
/**
* All provided callback functions must be non-blocking.
* This function is equivalent to \sa create_server()` however is using the individual
* node interfaces to create the server.
*
* \sa Server::Server() for more information.
*
* \param node[in] The action server will be added to this node.
* \param node_base_interface[in] The node base interface of the corresponding node.
* \param node_clock_interface[in] The node clock interface of the corresponding node.
* \param node_logging_interface[in] The node logging interface of the corresponding node.
* \param node_waitables_interface[in] The node waitables interface of the corresponding node.
* \param name[in] The action name.
* \param[in] handle_goal A callback that decides if a goal should be accepted or rejected.
* \param[in] handle_cancel A callback that decides if a goal should be attempted to be canceled.
Expand All @@ -51,7 +56,10 @@ namespace rclcpp_action
template<typename ActionT>
typename Server<ActionT>::SharedPtr
create_server(
rclcpp::Node::SharedPtr node,
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface,
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface,
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface,
const std::string & name,
typename Server<ActionT>::GoalCallback handle_goal,
typename Server<ActionT>::CancelCallback handle_cancel,
Expand All @@ -60,7 +68,7 @@ create_server(
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr)
{
std::weak_ptr<rclcpp::node_interfaces::NodeWaitablesInterface> weak_node =
node->get_node_waitables_interface();
node_waitables_interface;
std::weak_ptr<rclcpp::callback_group::CallbackGroup> weak_group = group;
bool group_is_null = (nullptr == group.get());

Expand Down Expand Up @@ -90,17 +98,58 @@ create_server(
};

std::shared_ptr<Server<ActionT>> action_server(new Server<ActionT>(
node->get_node_base_interface(),
node->get_node_clock_interface(),
node->get_node_logging_interface(),
node_base_interface,
node_clock_interface,
node_logging_interface,
name,
options,
handle_goal,
handle_cancel,
handle_accepted), deleter);

node->get_node_waitables_interface()->add_waitable(action_server, group);
node_waitables_interface->add_waitable(action_server, group);
return action_server;
}

/// Create an action server.
/**
* All provided callback functions must be non-blocking.
*
* \sa Server::Server() for more information.
*
* \param node[in] The action server will be added to this node.
* \param name[in] The action name.
* \param[in] handle_goal A callback that decides if a goal should be accepted or rejected.
* \param[in] handle_cancel A callback that decides if a goal should be attempted to be canceled.
* The return from this callback only indicates if the server will try to cancel a goal.
* It does not indicate if the goal was actually canceled.
* \param[in] handle_accepted A callback that is called to give the user a handle to the goal.
* \param[in] options options to pass to the underlying `rcl_action_server_t`.
* \param group[in] The action server will be added to this callback group.
* If `nullptr`, then the action server is added to the default callback group.
*/
template<typename ActionT>
typename Server<ActionT>::SharedPtr
create_server(
rclcpp::Node::SharedPtr node,
const std::string & name,
typename Server<ActionT>::GoalCallback handle_goal,
typename Server<ActionT>::CancelCallback handle_cancel,
typename Server<ActionT>::AcceptedCallback handle_accepted,
const rcl_action_server_options_t & options = rcl_action_server_get_default_options(),
rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr)
{
return create_server<ActionT>(
node->get_node_base_interface(),
node->get_node_clock_interface(),
node->get_node_logging_interface(),
node->get_node_waitables_interface(),
name,
handle_goal,
handle_cancel,
handle_accepted,
options,
group);
}
} // namespace rclcpp_action
#endif // RCLCPP_ACTION__CREATE_SERVER_HPP_