15 #ifndef RCLCPP_ACTION__CREATE_CLIENT_HPP_ 16 #define RCLCPP_ACTION__CREATE_CLIENT_HPP_ 28 template<
typename ActionT>
29 typename Client<ActionT>::SharedPtr
31 rclcpp::Node::SharedPtr node,
33 rclcpp::callback_group::CallbackGroup::SharedPtr group =
nullptr)
36 node->get_node_waitables_interface();
38 bool group_is_null = (
nullptr == group.get());
40 auto deleter = [weak_node, weak_group, group_is_null](
Client<ActionT> * ptr)
45 auto shared_node = weak_node.
lock();
54 shared_node->remove_waitable(fake_shared_ptr,
nullptr);
57 auto shared_group = weak_group.lock();
59 shared_node->remove_waitable(fake_shared_ptr, shared_group);
67 node->get_node_base_interface(),
68 node->get_node_graph_interface(),
69 node->get_node_logging_interface(),
73 node->get_node_waitables_interface()->add_waitable(action_client, group);
78 #endif // RCLCPP_ACTION__CREATE_CLIENT_HPP_
Action Client.
Definition: client.hpp:255
Client< ActionT >::SharedPtr create_client(rclcpp::Node::SharedPtr node, const std::string &name, rclcpp::callback_group::CallbackGroup::SharedPtr group=nullptr)
Definition: create_client.hpp:30
Definition: client.hpp:44