rclcpp_action  master
C++ ROS Action Client Library
create_server.hpp
Go to the documentation of this file.
1 // Copyright 2018 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef RCLCPP_ACTION__CREATE_SERVER_HPP_
16 #define RCLCPP_ACTION__CREATE_SERVER_HPP_
17 
18 #include <rcl_action/action_server.h>
19 
20 #include <rclcpp/node.hpp>
25 
26 #include <memory>
27 #include <string>
28 
29 #include "rclcpp_action/server.hpp"
31 
32 namespace rclcpp_action
33 {
35 
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,
63  const std::string & name,
64  typename Server<ActionT>::GoalCallback handle_goal,
65  typename Server<ActionT>::CancelCallback handle_cancel,
66  typename Server<ActionT>::AcceptedCallback handle_accepted,
67  const rcl_action_server_options_t & options = rcl_action_server_get_default_options(),
68  rclcpp::CallbackGroup::SharedPtr group = nullptr)
69 {
71  node_waitables_interface;
72  std::weak_ptr<rclcpp::CallbackGroup> weak_group = group;
73  bool group_is_null = (nullptr == group.get());
74 
75  auto deleter = [weak_node, weak_group, group_is_null](Server<ActionT> * ptr)
76  {
77  if (nullptr == ptr) {
78  return;
79  }
80  auto shared_node = weak_node.lock();
81  if (shared_node) {
82  // API expects a shared pointer, give it one with a deleter that does nothing.
83  std::shared_ptr<Server<ActionT>> fake_shared_ptr(ptr, [](Server<ActionT> *) {});
84 
85  if (group_is_null) {
86  // Was added to default group
87  shared_node->remove_waitable(fake_shared_ptr, nullptr);
88  } else {
89  // Was added to a specific group
90  auto shared_group = weak_group.lock();
91  if (shared_group) {
92  shared_node->remove_waitable(fake_shared_ptr, shared_group);
93  }
94  }
95  }
96  delete ptr;
97  };
98 
100  node_base_interface,
101  node_clock_interface,
102  node_logging_interface,
103  name,
104  options,
105  handle_goal,
106  handle_cancel,
107  handle_accepted), deleter);
108 
109  node_waitables_interface->add_waitable(action_server, group);
110  return action_server;
111 }
112 
114 
130 template<typename ActionT, typename NodeT>
131 typename Server<ActionT>::SharedPtr
133  NodeT node,
134  const std::string & name,
135  typename Server<ActionT>::GoalCallback handle_goal,
136  typename Server<ActionT>::CancelCallback handle_cancel,
137  typename Server<ActionT>::AcceptedCallback handle_accepted,
138  const rcl_action_server_options_t & options = rcl_action_server_get_default_options(),
139  rclcpp::CallbackGroup::SharedPtr group = nullptr)
140 {
141  return create_server<ActionT>(
142  node->get_node_base_interface(),
143  node->get_node_clock_interface(),
144  node->get_node_logging_interface(),
145  node->get_node_waitables_interface(),
146  name,
147  handle_goal,
148  handle_cancel,
149  handle_accepted,
150  options,
151  group);
152 }
153 } // namespace rclcpp_action
154 #endif // RCLCPP_ACTION__CREATE_SERVER_HPP_
node_logging_interface.hpp
std::weak_ptr::lock
T lock(T... args)
std::string
std::shared_ptr
node_clock_interface.hpp
node_base_interface.hpp
std::function< GoalResponse(const GoalUUID &, std::shared_ptr< const typename ActionT::Goal >)>
node.hpp
rclcpp_action
Definition: client.hpp:46
server.hpp
node_waitables_interface.hpp
rclcpp_action::create_server
Server< ActionT >::SharedPtr create_server(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface, rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface, rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface, const std::string &name, typename Server< ActionT >::GoalCallback handle_goal, typename Server< ActionT >::CancelCallback handle_cancel, typename Server< ActionT >::AcceptedCallback handle_accepted, const rcl_action_server_options_t &options=rcl_action_server_get_default_options(), rclcpp::CallbackGroup::SharedPtr group=nullptr)
Create an action server.
Definition: create_server.hpp:58
std::weak_ptr
rclcpp_action::Server
Action Server.
Definition: server.hpp:272
visibility_control.hpp
rcl_action_server_options_t