Class TransportHints
Defined in File transport_hints.hpp
Class Documentation
-
class TransportHints
Stores transport settings for an image topic subscription.
Public Functions
-
inline IMAGE_TRANSPORT_PUBLIC TransportHints(const rclcpp::Node *node, const std::string &default_transport = "raw", const std::string ¶meter_name = "image_transport")
Constructor.
The default transport can be overridden by setting a certain parameter to the name of the desired transport. By default this parameter is named “image_transport” in the node’s local namespace. For consistency across ROS applications, the name of this parameter should not be changed without good reason.
- Parameters:
node – Node to use when looking up the transport parameter.
default_transport – Preferred transport to use
parameter_name – The name of the transport parameter
- inline IMAGE_TRANSPORT_PUBLIC const std::string & getTransport () const
-
inline IMAGE_TRANSPORT_PUBLIC TransportHints(const rclcpp::Node *node, const std::string &default_transport = "raw", const std::string ¶meter_name = "image_transport")