15 #ifndef RCLCPP_ACTION__CREATE_SERVER_HPP_
16 #define RCLCPP_ACTION__CREATE_SERVER_HPP_
18 #include <rcl_action/action_server.h>
56 template<
typename ActionT>
57 typename Server<ActionT>::SharedPtr
59 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
60 rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface,
61 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface,
62 rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface,
68 rclcpp::CallbackGroup::SharedPtr group =
nullptr)
71 node_waitables_interface;
73 bool group_is_null = (
nullptr == group.get());
75 auto deleter = [weak_node, weak_group, group_is_null](
Server<ActionT> * ptr)
80 auto shared_node = weak_node.
lock();
89 shared_node->remove_waitable(fake_shared_ptr,
nullptr);
92 auto shared_group = weak_group.lock();
94 shared_node->remove_waitable(fake_shared_ptr, shared_group);
102 node_clock_interface,
103 node_logging_interface,
108 handle_accepted), deleter);
110 node_waitables_interface->add_waitable(action_server, group);
111 return action_server;
131 template<
typename ActionT,
typename NodeT>
132 typename Server<ActionT>::SharedPtr
140 rclcpp::CallbackGroup::SharedPtr group =
nullptr)
142 return create_server<ActionT>(
143 node->get_node_base_interface(),
144 node->get_node_clock_interface(),
145 node->get_node_logging_interface(),
146 node->get_node_waitables_interface(),
155 #endif // RCLCPP_ACTION__CREATE_SERVER_HPP_