rclcpp_action  master
C++ ROS Action Client Library
create_client.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_CLIENT_HPP_
16 #define RCLCPP_ACTION__CREATE_CLIENT_HPP_
17 
18 #include <rclcpp/node.hpp>
19 
20 #include <memory>
21 #include <string>
22 
23 #include "rclcpp_action/client.hpp"
25 
26 namespace rclcpp_action
27 {
29 
41 template<typename ActionT>
42 typename Client<ActionT>::SharedPtr
44  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
45  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface,
46  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface,
47  rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface,
48  const std::string & name,
49  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr)
50 {
52  node_waitables_interface;
54  bool group_is_null = (nullptr == group.get());
55 
56  auto deleter = [weak_node, weak_group, group_is_null](Client<ActionT> * ptr)
57  {
58  if (nullptr == ptr) {
59  return;
60  }
61  auto shared_node = weak_node.lock();
62  if (!shared_node) {
63  return;
64  }
65  // API expects a shared pointer, give it one with a deleter that does nothing.
66  std::shared_ptr<Client<ActionT>> fake_shared_ptr(ptr, [](Client<ActionT> *) {});
67 
68  if (group_is_null) {
69  // Was added to default group
70  shared_node->remove_waitable(fake_shared_ptr, nullptr);
71  } else {
72  // Was added to a specfic group
73  auto shared_group = weak_group.lock();
74  if (shared_group) {
75  shared_node->remove_waitable(fake_shared_ptr, shared_group);
76  }
77  }
78  delete ptr;
79  };
80 
81  std::shared_ptr<Client<ActionT>> action_client(
82  new Client<ActionT>(
83  node_base_interface,
84  node_graph_interface,
85  node_logging_interface,
86  name),
87  deleter);
88 
89  node_waitables_interface->add_waitable(action_client, group);
90  return action_client;
91 }
92 
94 
100 template<typename ActionT>
103  rclcpp::Node::SharedPtr node,
104  const std::string & name,
105  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr)
106 {
107  return create_client<ActionT>(
108  node->get_node_base_interface(),
109  node->get_node_graph_interface(),
110  node->get_node_logging_interface(),
111  node->get_node_waitables_interface(),
112  name,
113  group);
114 }
115 } // namespace rclcpp_action
116 
117 #endif // RCLCPP_ACTION__CREATE_CLIENT_HPP_
Action Client.
Definition: client.hpp:255
Client< ActionT >::SharedPtr create_client(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface, rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_interface, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface, rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface, const std::string &name, rclcpp::callback_group::CallbackGroup::SharedPtr group=nullptr)
Create an action client.
Definition: create_client.hpp:43
T lock(T... args)
Definition: client.hpp:44