Class GraphListener
Defined in File graph_listener.hpp
Inheritance Relationships
Base Type
public std::enable_shared_from_this< GraphListener >
Class Documentation
-
class GraphListener : public std::enable_shared_from_this<GraphListener>
Notifies many nodes of graph changes by listening in a thread.
Public Functions
-
virtual ~GraphListener()
-
virtual void start_if_not_started()
Start the graph listener’s listen thread if it hasn’t been started.
This function is thread-safe.
- Throws:
GraphListenerShutdownError – if the GraphListener is shutdown
std::runtime – if the parent context was destroyed
anything – rclcpp::exceptions::throw_from_rcl_error can throw.
-
virtual void add_node(rclcpp::node_interfaces::NodeGraphInterface *node_graph)
Add a node to the graph listener’s list of nodes.
- Throws:
GraphListenerShutdownError – if the GraphListener is shutdown
NodeAlreadyAddedError – if the given node is already in the list
std::invalid_argument – if node is nullptr
std::system_error – anything std::mutex::lock() throws
-
virtual bool has_node(rclcpp::node_interfaces::NodeGraphInterface *node_graph)
Return true if the given node is in the graph listener’s list of nodes.
Also return false if given nullptr.
- Throws:
std::system_error – anything std::mutex::lock() throws
-
virtual void remove_node(rclcpp::node_interfaces::NodeGraphInterface *node_graph)
Remove a node from the graph listener’s list of nodes.
- Throws:
NodeNotFoundError – if the given node is not in the list
std::invalid_argument – if node is nullptr
std::system_error – anything std::mutex::lock() throws
-
virtual void shutdown()
Stop the listening thread.
The thread cannot be restarted, and the class is defunct after calling. This function is called by the ~GraphListener() and does nothing if shutdown() was already called. This function exists separately from the ~GraphListener() so that it can be called before and exceptions can be caught.
If start_if_not_started() was never called, this function still succeeds, but start_if_not_started() still cannot be called after this function.
- Throws:
rclcpp::execptions::RCLError – from rcl_guard_condition_fini()
rclcpp::execptions::RCLError – from rcl_wait_set_fini()
std::system_error – anything std::mutex::lock() throws
-
virtual void shutdown(const std::nothrow_t&) noexcept
Nothrow version of shutdown(), logs to RCLCPP_ERROR instead.
-
virtual bool is_shutdown()
Return true if shutdown() has been called, else false.
-
virtual ~GraphListener()