15 #ifndef RCLCPP_ACTION__CREATE_CLIENT_HPP_ 16 #define RCLCPP_ACTION__CREATE_CLIENT_HPP_ 41 template<
typename ActionT>
42 typename Client<ActionT>::SharedPtr
44 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
45 rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
46 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface,
47 rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface,
49 rclcpp::callback_group::CallbackGroup::SharedPtr group =
nullptr)
52 node_waitables_interface;
54 bool group_is_null = (
nullptr == group.get());
56 auto deleter = [weak_node, weak_group, group_is_null](
Client<ActionT> * ptr)
61 auto shared_node = weak_node.
lock();
70 shared_node->remove_waitable(fake_shared_ptr,
nullptr);
73 auto shared_group = weak_group.lock();
75 shared_node->remove_waitable(fake_shared_ptr, shared_group);
85 node_logging_interface,
89 node_waitables_interface->add_waitable(action_client, group);
100 template<
typename ActionT>
103 rclcpp::Node::SharedPtr node,
105 rclcpp::callback_group::CallbackGroup::SharedPtr group =
nullptr)
107 return create_client<ActionT>(
108 node->get_node_base_interface(),
109 node->get_node_graph_interface(),
110 node->get_node_logging_interface(),
111 node->get_node_waitables_interface(),
117 #endif // RCLCPP_ACTION__CREATE_CLIENT_HPP_
Action Client.
Definition: client.hpp:255
Client< ActionT >::SharedPtr create_client(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)
Create an action client.
Definition: create_client.hpp:43
Definition: client.hpp:44