rclcpp
master
C++ ROS Client Library API
|
Go to the documentation of this file.
15 #ifndef RCLCPP__NODE_INTERFACES__NODE_GRAPH_INTERFACE_HPP_
16 #define RCLCPP__NODE_INTERFACES__NODE_GRAPH_INTERFACE_HPP_
60 std::copy(info.endpoint_gid, info.endpoint_gid + RMW_GID_STORAGE_SIZE, endpoint_gid_.
begin());
132 namespace node_interfaces
256 rclcpp::Event::SharedPtr
271 rclcpp::Event::SharedPtr event,
307 #endif // RCLCPP__NODE_INTERFACES__NODE_GRAPH_INTERFACE_HPP_
std::string & topic_type()
Get a mutable reference to the topic type string.
A publisher publishes messages of any type to a topic.
Definition: publisher.hpp:53
virtual rclcpp::Event::SharedPtr get_graph_event()=0
Return a graph event, which will be set anytime a graph change occurs.
virtual size_t count_graph_users() const =0
Return the number of on loan graph events, see get_graph_event().
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.
#define RCLCPP_SMART_PTR_ALIASES_ONLY(...)
Definition: macros.hpp:66
std::array< uint8_t, RMW_GID_STORAGE_SIZE > & endpoint_gid()
Get a mutable reference to the GID of the topic endpoint.
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
Subscription implementation, templated on the type of message this subscription receives.
Definition: subscription.hpp:69
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.
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
Encapsulation of Quality of Service settings.
Definition: qos.hpp:110
EndpointType
Definition: node_graph_interface.hpp:37
virtual void notify_graph_change()=0
Notify threads waiting on graph changes.
rclcpp::EndpointType & endpoint_type()
Get a mutable reference to the topic endpoint type.
virtual std::vector< std::string > get_node_names() const =0
Return a vector of existing node names (string).
rclcpp::QoS & qos_profile()
Get a mutable reference to the QoS profile of the topic endpoint.
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.
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.
enum rmw_qos_history_policy_t history
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_qos_profile_t qos_profile
virtual size_t count_publishers(const std::string &topic_name) const =0
Return the number of publishers that are advertised on a given topic.
virtual void notify_shutdown()=0
Notify any and all blocking node actions that shutdown has occurred.
Definition: node_graph_interface.hpp:48
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.
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.
virtual ~NodeGraphInterface()=default
Pure virtual interface class for the NodeGraph part of the Node API.
Definition: node_graph_interface.hpp:136
std::string & node_namespace()
Get a mutable reference to the node namespace.
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).
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.
std::string & node_name()
Get a mutable reference to the node name.
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.