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 
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 {
34 template<typename ActionT>
35 typename Server<ActionT>::SharedPtr
37  rclcpp::Node::SharedPtr node,
38  const std::string & name,
39  typename Server<ActionT>::GoalCallback handle_goal,
40  typename Server<ActionT>::CancelCallback handle_cancel,
41  typename Server<ActionT>::AcceptedCallback handle_accepted,
43  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr)
44 {
46  node->get_node_waitables_interface();
48  bool group_is_null = (nullptr == group.get());
49 
50  auto deleter = [weak_node, weak_group, group_is_null](Server<ActionT> * ptr)
51  {
52  if (nullptr == ptr) {
53  return;
54  }
55  auto shared_node = weak_node.lock();
56  if (!shared_node) {
57  return;
58  }
59  // API expects a shared pointer, give it one with a deleter that does nothing.
60  std::shared_ptr<Server<ActionT>> fake_shared_ptr(ptr, [](Server<ActionT> *) {});
61 
62  if (group_is_null) {
63  // Was added to default group
64  shared_node->remove_waitable(fake_shared_ptr, nullptr);
65  } else {
66  // Was added to a specfic group
67  auto shared_group = weak_group.lock();
68  if (shared_group) {
69  shared_node->remove_waitable(fake_shared_ptr, shared_group);
70  }
71  }
72  delete ptr;
73  };
74 
76  node->get_node_base_interface(),
77  node->get_node_clock_interface(),
78  node->get_node_logging_interface(),
79  name,
80  options,
81  handle_goal,
82  handle_cancel,
83  handle_accepted), deleter);
84 
85  node->get_node_waitables_interface()->add_waitable(action_server, group);
86  return action_server;
87 }
88 } // namespace rclcpp_action
89 #endif // RCLCPP_ACTION__CREATE_SERVER_HPP_
Server< ActionT >::SharedPtr create_server(rclcpp::Node::SharedPtr node, 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::callback_group::CallbackGroup::SharedPtr group=nullptr)
Definition: create_server.hpp:36
RCL_ACTION_PUBLIC rcl_action_server_options_t rcl_action_server_get_default_options(void)
Action Server.
Definition: server.hpp:268
T lock(T... args)
Definition: client.hpp:44