15 #ifndef RCLCPP_ACTION__CREATE_CLIENT_HPP_
16 #define RCLCPP_ACTION__CREATE_CLIENT_HPP_
42 template<
typename ActionT>
43 typename Client<ActionT>::SharedPtr
45 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
46 rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
47 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface,
48 rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface,
50 rclcpp::CallbackGroup::SharedPtr group =
nullptr,
54 node_waitables_interface;
56 bool group_is_null = (
nullptr == group.get());
58 auto deleter = [weak_node, weak_group, group_is_null](
Client<ActionT> * ptr)
63 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);
86 node_logging_interface,
91 node_waitables_interface->add_waitable(action_client, group);
103 template<
typename ActionT,
typename NodeT>
104 typename Client<ActionT>::SharedPtr
108 rclcpp::CallbackGroup::SharedPtr group =
nullptr,
111 return rclcpp_action::create_client<ActionT>(
112 node->get_node_base_interface(),
113 node->get_node_graph_interface(),
114 node->get_node_logging_interface(),
115 node->get_node_waitables_interface(),
122 #endif // RCLCPP_ACTION__CREATE_CLIENT_HPP_