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 {
28 template<typename ActionT>
29 typename Client<ActionT>::SharedPtr
31  rclcpp::Node::SharedPtr node,
32  const std::string & name,
33  rclcpp::callback_group::CallbackGroup::SharedPtr group = nullptr)
34 {
36  node->get_node_waitables_interface();
38  bool group_is_null = (nullptr == group.get());
39 
40  auto deleter = [weak_node, weak_group, group_is_null](Client<ActionT> * ptr)
41  {
42  if (nullptr == ptr) {
43  return;
44  }
45  auto shared_node = weak_node.lock();
46  if (!shared_node) {
47  return;
48  }
49  // API expects a shared pointer, give it one with a deleter that does nothing.
50  std::shared_ptr<Client<ActionT>> fake_shared_ptr(ptr, [](Client<ActionT> *) {});
51 
52  if (group_is_null) {
53  // Was added to default group
54  shared_node->remove_waitable(fake_shared_ptr, nullptr);
55  } else {
56  // Was added to a specfic group
57  auto shared_group = weak_group.lock();
58  if (shared_group) {
59  shared_node->remove_waitable(fake_shared_ptr, shared_group);
60  }
61  }
62  delete ptr;
63  };
64 
65  std::shared_ptr<Client<ActionT>> action_client(
66  new Client<ActionT>(
67  node->get_node_base_interface(),
68  node->get_node_graph_interface(),
69  node->get_node_logging_interface(),
70  name),
71  deleter);
72 
73  node->get_node_waitables_interface()->add_waitable(action_client, group);
74  return action_client;
75 }
76 } // namespace rclcpp_action
77 
78 #endif // RCLCPP_ACTION__CREATE_CLIENT_HPP_
Action Client.
Definition: client.hpp:255
T lock(T... args)
Client< ActionT >::SharedPtr create_client(rclcpp::Node::SharedPtr node, const std::string &name, rclcpp::callback_group::CallbackGroup::SharedPtr group=nullptr)
Definition: create_client.hpp:30
Definition: client.hpp:44