ROS 2 rclcpp + rcl - kilted  kilted
ROS 2 C++ Client Library with ROS Client Library
node_graph_interface.hpp
1 // Copyright 2016-2017 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__NODE_INTERFACES__NODE_GRAPH_INTERFACE_HPP_
16 #define RCLCPP__NODE_INTERFACES__NODE_GRAPH_INTERFACE_HPP_
17 
18 #include <algorithm>
19 #include <array>
20 #include <chrono>
21 #include <map>
22 #include <string>
23 #include <tuple>
24 #include <utility>
25 #include <vector>
26 
27 #include "rcl/graph.h"
28 #include "rcl/guard_condition.h"
29 
30 #include "rclcpp/event.hpp"
31 #include "rclcpp/macros.hpp"
32 #include "rclcpp/node_interfaces/detail/node_interfaces_helpers.hpp"
33 #include "rclcpp/qos.hpp"
34 #include "rclcpp/visibility_control.hpp"
35 
36 namespace rclcpp
37 {
38 
39 enum class EndpointType
40 {
41  Invalid = RMW_ENDPOINT_INVALID,
42  Publisher = RMW_ENDPOINT_PUBLISHER,
43  Subscription = RMW_ENDPOINT_SUBSCRIPTION
44 };
45 
51 {
52 public:
54  RCLCPP_PUBLIC
56  : node_name_(info.node_name),
57  node_namespace_(info.node_namespace),
58  topic_type_(info.topic_type),
59  endpoint_type_(static_cast<rclcpp::EndpointType>(info.endpoint_type)),
60  qos_profile_({info.qos_profile.history, info.qos_profile.depth}, info.qos_profile),
61  topic_type_hash_(info.topic_type_hash)
62  {
63  std::copy(info.endpoint_gid, info.endpoint_gid + RMW_GID_STORAGE_SIZE, endpoint_gid_.begin());
64  }
65 
67  RCLCPP_PUBLIC
68  std::string &
69  node_name();
70 
72  RCLCPP_PUBLIC
73  const std::string &
74  node_name() const;
75 
77  RCLCPP_PUBLIC
78  std::string &
80 
82  RCLCPP_PUBLIC
83  const std::string &
84  node_namespace() const;
85 
87  RCLCPP_PUBLIC
88  std::string &
89  topic_type();
90 
92  RCLCPP_PUBLIC
93  const std::string &
94  topic_type() const;
95 
97  RCLCPP_PUBLIC
98  rclcpp::EndpointType &
99  endpoint_type();
100 
102  RCLCPP_PUBLIC
103  const rclcpp::EndpointType &
104  endpoint_type() const;
105 
107  RCLCPP_PUBLIC
108  std::array<uint8_t, RMW_GID_STORAGE_SIZE> &
109  endpoint_gid();
110 
112  RCLCPP_PUBLIC
113  const std::array<uint8_t, RMW_GID_STORAGE_SIZE> &
114  endpoint_gid() const;
115 
117  RCLCPP_PUBLIC
118  rclcpp::QoS &
119  qos_profile();
120 
122  RCLCPP_PUBLIC
123  const rclcpp::QoS &
124  qos_profile() const;
125 
127  RCLCPP_PUBLIC
128  rosidl_type_hash_t &
129  topic_type_hash();
130 
132  RCLCPP_PUBLIC
133  const rosidl_type_hash_t &
134  topic_type_hash() const;
135 
136 private:
137  std::string node_name_;
138  std::string node_namespace_;
139  std::string topic_type_;
140  rclcpp::EndpointType endpoint_type_;
141  std::array<uint8_t, RMW_GID_STORAGE_SIZE> endpoint_gid_;
142  rclcpp::QoS qos_profile_;
143  rosidl_type_hash_t topic_type_hash_;
144 };
145 
146 namespace node_interfaces
147 {
148 
151 {
152 public:
153  RCLCPP_SMART_PTR_ALIASES_ONLY(NodeGraphInterface)
154 
155  RCLCPP_PUBLIC
156  virtual
157  ~NodeGraphInterface() = default;
158 
160 
169  RCLCPP_PUBLIC
170  virtual
171  std::map<std::string, std::vector<std::string>>
172  get_topic_names_and_types(bool no_demangle = false) const = 0;
173 
175 
183  RCLCPP_PUBLIC
184  virtual
185  std::map<std::string, std::vector<std::string>>
187 
189 
198  RCLCPP_PUBLIC
199  virtual
200  std::map<std::string, std::vector<std::string>>
202  const std::string & node_name,
203  const std::string & namespace_) const = 0;
204 
206 
215  RCLCPP_PUBLIC
216  virtual
217  std::map<std::string, std::vector<std::string>>
219  const std::string & node_name,
220  const std::string & namespace_) const = 0;
221 
223 
233  RCLCPP_PUBLIC
234  virtual
235  std::map<std::string, std::vector<std::string>>
237  const std::string & node_name,
238  const std::string & namespace_,
239  bool no_demangle = false) const = 0;
240 
242 
252  RCLCPP_PUBLIC
253  virtual
254  std::map<std::string, std::vector<std::string>>
256  const std::string & node_name,
257  const std::string & namespace_,
258  bool no_demangle = false) const = 0;
259 
261  /*
262  * The returned names are the actual names after remap rules applied.
263  */
264  RCLCPP_PUBLIC
265  virtual
266  std::vector<std::string>
267  get_node_names() const = 0;
268 
270  /*
271  * The returned names are the actual names after remap rules applied.
272  * The enclaves contain the runtime security artifacts, those can be
273  * used to establish secured network.
274  * See https://design.ros2.org/articles/ros2_security_enclaves.html
275  */
276  RCLCPP_PUBLIC
277  virtual
278  std::vector<std::tuple<std::string, std::string, std::string>>
280 
282  /*
283  * The returned names are the actual names after remap rules applied.
284  */
285  RCLCPP_PUBLIC
286  virtual
287  std::vector<std::pair<std::string, std::string>>
289 
291  /*
292  * \param[in] topic_name the actual topic name used; it will not be automatically remapped.
293  */
294  RCLCPP_PUBLIC
295  virtual
296  size_t
297  count_publishers(const std::string & topic_name) const = 0;
298 
300  /*
301  * \param[in] topic_name the actual topic name used; it will not be automatically remapped.
302  */
303  RCLCPP_PUBLIC
304  virtual
305  size_t
306  count_subscribers(const std::string & topic_name) const = 0;
307 
309  /*
310  * \param[in] service_name the actual service name used; it will not be automatically remapped.
311  */
312  RCLCPP_PUBLIC
313  virtual
314  size_t
315  count_clients(const std::string & service_name) const = 0;
316 
318  /*
319  * \param[in] service_name the actual service name used; it will not be automatically remapped.
320  */
321  RCLCPP_PUBLIC
322  virtual
323  size_t
324  count_services(const std::string & service_name) const = 0;
325 
327  RCLCPP_PUBLIC
328  virtual
329  const rcl_guard_condition_t *
331 
333 
342  RCLCPP_PUBLIC
343  virtual
344  void
346 
348  RCLCPP_PUBLIC
349  virtual
350  void
352 
354 
359  RCLCPP_PUBLIC
360  virtual
361  rclcpp::Event::SharedPtr
363 
365 
372  RCLCPP_PUBLIC
373  virtual
374  void
376  rclcpp::Event::SharedPtr event,
377  std::chrono::nanoseconds timeout) = 0;
378 
380 
383  RCLCPP_PUBLIC
384  virtual
385  size_t
386  count_graph_users() const = 0;
387 
389 
395  RCLCPP_PUBLIC
396  virtual
397  std::vector<rclcpp::TopicEndpointInfo>
398  get_publishers_info_by_topic(const std::string & topic_name, bool no_mangle = false) const = 0;
399 
401 
407  RCLCPP_PUBLIC
408  virtual
409  std::vector<rclcpp::TopicEndpointInfo>
410  get_subscriptions_info_by_topic(const std::string & topic_name, bool no_mangle = false) const = 0;
411 };
412 
413 } // namespace node_interfaces
414 } // namespace rclcpp
415 
416 RCLCPP_NODE_INTERFACE_HELPERS_SUPPORT(rclcpp::node_interfaces::NodeGraphInterface, graph)
417 
418 #endif // RCLCPP__NODE_INTERFACES__NODE_GRAPH_INTERFACE_HPP_
Encapsulation of Quality of Service settings.
Definition: qos.hpp:116
RCLCPP_PUBLIC TopicEndpointInfo(const rcl_topic_endpoint_info_t &info)
Construct a TopicEndpointInfo from a rcl_topic_endpoint_info_t.
RCLCPP_PUBLIC std::string & node_name()
Get a mutable reference to the node name.
Definition: node_graph.cpp:765
RCLCPP_PUBLIC std::string & node_namespace()
Get a mutable reference to the node namespace.
Definition: node_graph.cpp:777
RCLCPP_PUBLIC rosidl_type_hash_t & topic_type_hash()
Get a mutable reference to the type hash of the topic endpoint.
Definition: node_graph.cpp:837
RCLCPP_PUBLIC std::string & topic_type()
Get a mutable reference to the topic type string.
Definition: node_graph.cpp:789
RCLCPP_PUBLIC rclcpp::QoS & qos_profile()
Get a mutable reference to the QoS profile of the topic endpoint.
Definition: node_graph.cpp:825
RCLCPP_PUBLIC rclcpp::EndpointType & endpoint_type()
Get a mutable reference to the topic endpoint type.
Definition: node_graph.cpp:801
RCLCPP_PUBLIC std::array< uint8_t, RMW_GID_STORAGE_SIZE > & endpoint_gid()
Get a mutable reference to the GID of the topic endpoint.
Definition: node_graph.cpp:813
Pure virtual interface class for the NodeGraph part of the Node API.
virtual RCLCPP_PUBLIC rclcpp::Event::SharedPtr get_graph_event()=0
Return a graph event, which will be set anytime a graph change occurs.
virtual RCLCPP_PUBLIC std::map< std::string, std::vector< std::string > > get_client_names_and_types_by_node(const std::string &node_name, const std::string &namespace_) const =0
Return a map of existing service names and types with a specific node.
virtual RCLCPP_PUBLIC size_t count_clients(const std::string &service_name) const =0
Return the number of clients created for a given service.
virtual RCLCPP_PUBLIC std::map< std::string, std::vector< std::string > > get_subscriber_names_and_types_by_node(const std::string &node_name, const std::string &namespace_, bool no_demangle=false) const =0
Return a map of existing topic names to list of topic types for a specific node.
virtual RCLCPP_PUBLIC std::vector< std::pair< std::string, std::string > > get_node_names_and_namespaces() const =0
Return a vector of existing node names and namespaces (pair of string).
virtual RCLCPP_PUBLIC std::vector< rclcpp::TopicEndpointInfo > get_subscriptions_info_by_topic(const std::string &topic_name, bool no_mangle=false) const =0
Return the topic endpoint information about subscriptions on a given topic.
virtual RCLCPP_PUBLIC std::map< std::string, std::vector< std::string > > get_publisher_names_and_types_by_node(const std::string &node_name, const std::string &namespace_, bool no_demangle=false) const =0
Return a map of existing topic names to list of topic types for a specific node.
virtual RCLCPP_PUBLIC void notify_shutdown()=0
Notify any and all blocking node actions that shutdown has occurred.
virtual RCLCPP_PUBLIC std::vector< std::tuple< std::string, std::string, std::string > > get_node_names_with_enclaves() const =0
Return a vector of existing node names, namespaces and enclaves (tuple of string).
virtual RCLCPP_PUBLIC size_t count_subscribers(const std::string &topic_name) const =0
Return the number of subscribers who have created a subscription for a given topic.
virtual RCLCPP_PUBLIC size_t count_services(const std::string &service_name) const =0
Return the number of services created for a given service.
virtual RCLCPP_PUBLIC std::map< std::string, std::vector< std::string > > get_service_names_and_types_by_node(const std::string &node_name, const std::string &namespace_) const =0
Return a map of existing service names to list of service types for a specific node.
virtual RCLCPP_PUBLIC std::vector< rclcpp::TopicEndpointInfo > get_publishers_info_by_topic(const std::string &topic_name, bool no_mangle=false) const =0
Return the topic endpoint information about publishers on a given topic.
virtual RCLCPP_PUBLIC void notify_graph_change()=0
Notify threads waiting on graph changes.
virtual RCLCPP_PUBLIC std::map< std::string, std::vector< std::string > > get_service_names_and_types() const =0
Return a map of existing service names to list of service types.
virtual RCLCPP_PUBLIC std::vector< std::string > get_node_names() const =0
Return a vector of existing node names (string).
virtual RCLCPP_PUBLIC size_t count_graph_users() const =0
Return the number of on loan graph events, see get_graph_event().
virtual RCLCPP_PUBLIC void wait_for_graph_change(rclcpp::Event::SharedPtr event, std::chrono::nanoseconds timeout)=0
Wait for a graph event to occur by waiting on an Event to become set.
virtual RCLCPP_PUBLIC std::map< std::string, std::vector< std::string > > get_topic_names_and_types(bool no_demangle=false) const =0
Return a map of existing topic names to list of topic types.
virtual RCLCPP_PUBLIC const rcl_guard_condition_t * get_graph_guard_condition() const =0
Return the rcl guard condition which is triggered when the ROS graph changes.
virtual RCLCPP_PUBLIC size_t count_publishers(const std::string &topic_name) const =0
Return the number of publishers that are advertised on a given topic.
rmw_topic_endpoint_info_t rcl_topic_endpoint_info_t
Definition: graph.h:45
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
Handle for a rcl guard condition.