@@ -63,6 +63,26 @@ class Node : public rclcpp::Node {
6363 return action_server;
6464 }
6565
66+ template <typename ActionT>
67+ typename std::shared_ptr<actions::ActionSingleServer<ActionT>>
68+ create_action_server (
69+ std::string action_name,
70+ std::function<
71+ void (std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>>)>
72+ execute_callback,
73+ std::function<void()> cancel_callback) {
74+
75+ rclcpp::CallbackGroup::SharedPtr group = nullptr ;
76+
77+ std::shared_ptr<actions::ActionSingleServer<ActionT>> action_server (
78+ new actions::ActionSingleServer<ActionT>(
79+ this , action_name, execute_callback, cancel_callback),
80+ this ->create_action_deleter <rclcpp_action::Server<ActionT>>(group));
81+
82+ this ->get_node_waitables_interface ()->add_waitable (action_server, group);
83+ return action_server;
84+ }
85+
6686 template <typename ActionT>
6787 typename std::shared_ptr<actions::ActionQueueServer<ActionT>>
6888 create_action_queue_server (
@@ -82,6 +102,26 @@ class Node : public rclcpp::Node {
82102 return action_server;
83103 }
84104
105+ template <typename ActionT>
106+ typename std::shared_ptr<actions::ActionQueueServer<ActionT>>
107+ create_action_queue_server (
108+ std::string action_name,
109+ std::function<
110+ void (std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>>)>
111+ execute_callback,
112+ std::function<void()> cancel_callback) {
113+
114+ rclcpp::CallbackGroup::SharedPtr group = nullptr ;
115+
116+ std::shared_ptr<actions::ActionQueueServer<ActionT>> action_server (
117+ new actions::ActionQueueServer<ActionT>(
118+ this , action_name, execute_callback, cancel_callback),
119+ this ->create_action_deleter <rclcpp_action::Server<ActionT>>(group));
120+
121+ this ->get_node_waitables_interface ()->add_waitable (action_server, group);
122+ return action_server;
123+ }
124+
85125private:
86126 rclcpp::Executor *executor;
87127 std::thread *spin_thread;
0 commit comments