rclcpp  master
C++ ROS Client Library API
node_graph_interface.hpp
Go to the documentation of this file.
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 <utility>
24 #include <vector>
25 
26 #include "rcl/graph.h"
27 #include "rcl/guard_condition.h"
28 
29 #include "rclcpp/event.hpp"
30 #include "rclcpp/macros.hpp"
31 #include "rclcpp/qos.hpp"
33 
34 namespace rclcpp
35 {
36 
37 enum class EndpointType
38 {
41  Subscription = RMW_ENDPOINT_SUBSCRIPTION
42 };
43 
49 {
50 public:
54  : node_name_(info.node_name),
55  node_namespace_(info.node_namespace),
56  topic_type_(info.topic_type),
57  endpoint_type_(static_cast<rclcpp::EndpointType>(info.endpoint_type)),
58  qos_profile_({info.qos_profile.history, info.qos_profile.depth}, info.qos_profile)
59  {
60  std::copy(info.endpoint_gid, info.endpoint_gid + RMW_GID_STORAGE_SIZE, endpoint_gid_.begin());
61  }
62 
65  std::string &
66  node_name();
67 
70  const std::string &
71  node_name() const;
72 
75  std::string &
77 
80  const std::string &
81  node_namespace() const;
82 
85  std::string &
86  topic_type();
87 
90  const std::string &
91  topic_type() const;
92 
96  endpoint_type();
97 
100  const rclcpp::EndpointType &
101  endpoint_type() const;
102 
106  endpoint_gid();
107 
111  endpoint_gid() const;
112 
115  rclcpp::QoS &
116  qos_profile();
117 
120  const rclcpp::QoS &
121  qos_profile() const;
122 
123 private:
124  std::string node_name_;
125  std::string node_namespace_;
126  std::string topic_type_;
127  rclcpp::EndpointType endpoint_type_;
129  rclcpp::QoS qos_profile_;
130 };
131 
132 namespace node_interfaces
133 {
134 
137 {
138 public:
140 
142  virtual
143  ~NodeGraphInterface() = default;
144 
146 
154  virtual
156  get_topic_names_and_types(bool no_demangle = false) const = 0;
157 
159 
166  virtual
168  get_service_names_and_types() const = 0;
169 
171 
179  virtual
182  const std::string & node_name,
183  const std::string & namespace_) const = 0;
184 
186  /*
187  * The returned names are the actual names used and do not have remap rules applied.
188  */
190  virtual
192  get_node_names() const = 0;
193 
195  /*
196  * The returned names are the actual names used and do not have remap rules applied.
197  */
199  virtual
201  get_node_names_and_namespaces() const = 0;
202 
204  /*
205  * \param[in] topic_name the actual topic name used; it will not be automatically remapped.
206  */
208  virtual
209  size_t
210  count_publishers(const std::string & topic_name) const = 0;
211 
213  /*
214  * \param[in] topic_name the actual topic name used; it will not be automatically remapped.
215  */
217  virtual
218  size_t
219  count_subscribers(const std::string & topic_name) const = 0;
220 
223  virtual
224  const rcl_guard_condition_t *
225  get_graph_guard_condition() const = 0;
226 
228 
238  virtual
239  void
240  notify_graph_change() = 0;
241 
244  virtual
245  void
246  notify_shutdown() = 0;
247 
249 
255  virtual
256  rclcpp::Event::SharedPtr
257  get_graph_event() = 0;
258 
260 
268  virtual
269  void
271  rclcpp::Event::SharedPtr event,
272  std::chrono::nanoseconds timeout) = 0;
273 
275 
279  virtual
280  size_t
281  count_graph_users() const = 0;
282 
284 
289  virtual
291  get_publishers_info_by_topic(const std::string & topic_name, bool no_mangle = false) const = 0;
292 
294 
299  virtual
301  get_subscriptions_info_by_topic(const std::string & topic_name, bool no_mangle = false) const = 0;
302 };
303 
304 } // namespace node_interfaces
305 } // namespace rclcpp
306 
307 #endif // RCLCPP__NODE_INTERFACES__NODE_GRAPH_INTERFACE_HPP_
rclcpp::TopicEndpointInfo::topic_type
std::string & topic_type()
Get a mutable reference to the topic type string.
graph.h
std::string
rclcpp::Publisher
A publisher publishes messages of any type to a topic.
Definition: publisher.hpp:53
rclcpp::node_interfaces::NodeGraphInterface::get_graph_event
virtual rclcpp::Event::SharedPtr get_graph_event()=0
Return a graph event, which will be set anytime a graph change occurs.
guard_condition.h
rclcpp::node_interfaces::NodeGraphInterface::count_graph_users
virtual size_t count_graph_users() const =0
Return the number of on loan graph events, see get_graph_event().
rclcpp::node_interfaces::NodeGraphInterface::count_subscribers
virtual 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.
std::vector< std::string >
std::chrono::nanoseconds
RCLCPP_SMART_PTR_ALIASES_ONLY
#define RCLCPP_SMART_PTR_ALIASES_ONLY(...)
Definition: macros.hpp:66
event.hpp
rclcpp::TopicEndpointInfo::endpoint_gid
std::array< uint8_t, RMW_GID_STORAGE_SIZE > & endpoint_gid()
Get a mutable reference to the GID of the topic endpoint.
rcl_guard_condition_t
rclcpp::EndpointType::Invalid
@ Invalid
rclcpp
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
qos.hpp
rclcpp::Subscription
Subscription implementation, templated on the type of message this subscription receives.
Definition: subscription.hpp:69
rclcpp::node_interfaces::NodeGraphInterface::get_publishers_info_by_topic
virtual 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.
RCLCPP_PUBLIC
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
rclcpp::QoS
Encapsulation of Quality of Service settings.
Definition: qos.hpp:110
rclcpp::EndpointType
EndpointType
Definition: node_graph_interface.hpp:37
macros.hpp
rclcpp::node_interfaces::NodeGraphInterface::notify_graph_change
virtual void notify_graph_change()=0
Notify threads waiting on graph changes.
rclcpp::TopicEndpointInfo::endpoint_type
rclcpp::EndpointType & endpoint_type()
Get a mutable reference to the topic endpoint type.
rclcpp::node_interfaces::NodeGraphInterface::get_node_names
virtual std::vector< std::string > get_node_names() const =0
Return a vector of existing node names (string).
rclcpp::TopicEndpointInfo::qos_profile
rclcpp::QoS & qos_profile()
Get a mutable reference to the QoS profile of the topic endpoint.
rclcpp::node_interfaces::NodeGraphInterface::get_topic_names_and_types
virtual 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.
std::array< uint8_t, RMW_GID_STORAGE_SIZE >
rclcpp::node_interfaces::NodeGraphInterface::get_graph_guard_condition
virtual const rcl_guard_condition_t * get_graph_guard_condition() const =0
Return the rcl guard condition which is triggered when the ROS graph changes.
std::copy
T copy(T... args)
rmw_qos_profile_t::history
enum rmw_qos_history_policy_t history
std::map
rclcpp::TopicEndpointInfo::TopicEndpointInfo
TopicEndpointInfo(const rcl_topic_endpoint_info_t &info)
Construct a TopicEndpointInfo from a rcl_topic_endpoint_info_t.
Definition: node_graph_interface.hpp:53
rmw_topic_endpoint_info_t::qos_profile
rmw_qos_profile_t qos_profile
rclcpp::node_interfaces::NodeGraphInterface::count_publishers
virtual size_t count_publishers(const std::string &topic_name) const =0
Return the number of publishers that are advertised on a given topic.
rclcpp::node_interfaces::NodeGraphInterface::notify_shutdown
virtual void notify_shutdown()=0
Notify any and all blocking node actions that shutdown has occurred.
rclcpp::TopicEndpointInfo
Definition: node_graph_interface.hpp:48
rmw_topic_endpoint_info_t
rclcpp::node_interfaces::NodeGraphInterface::get_service_names_and_types_by_node
virtual 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.
rclcpp::node_interfaces::NodeGraphInterface::get_service_names_and_types
virtual 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.
rclcpp::node_interfaces::NodeGraphInterface::~NodeGraphInterface
virtual ~NodeGraphInterface()=default
std::array::begin
T begin(T... args)
visibility_control.hpp
RMW_ENDPOINT_INVALID
RMW_ENDPOINT_INVALID
rclcpp::node_interfaces::NodeGraphInterface
Pure virtual interface class for the NodeGraph part of the Node API.
Definition: node_graph_interface.hpp:136
rclcpp::TopicEndpointInfo::node_namespace
std::string & node_namespace()
Get a mutable reference to the node namespace.
rclcpp::node_interfaces::NodeGraphInterface::get_node_names_and_namespaces
virtual 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).
RMW_ENDPOINT_PUBLISHER
RMW_ENDPOINT_PUBLISHER
rclcpp::node_interfaces::NodeGraphInterface::wait_for_graph_change
virtual 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.
rclcpp::TopicEndpointInfo::node_name
std::string & node_name()
Get a mutable reference to the node name.
rmw_qos_profile_t::depth
size_t depth
rclcpp::node_interfaces::NodeGraphInterface::get_subscriptions_info_by_topic
virtual 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.