Stores transport settings for an image topic subscription. More...
#include <transport_hints.h>
Public Member Functions | |
const ros::NodeHandle & | getParameterNH () const |
const ros::TransportHints & | getRosHints () const |
const std::string & | getTransport () const |
TransportHints (const std::string &default_transport="raw", const ros::TransportHints &ros_hints=ros::TransportHints(), const ros::NodeHandle ¶meter_nh=ros::NodeHandle("~"), const std::string ¶meter_name="message_transport") | |
Constructor. | |
Private Attributes | |
ros::NodeHandle | parameter_nh_ |
ros::TransportHints | ros_hints_ |
std::string | transport_ |
Stores transport settings for an image topic subscription.
Definition at line 11 of file transport_hints.h.
message_transport::TransportHints::TransportHints | ( | const std::string & | default_transport = "raw" , |
|
const ros::TransportHints & | ros_hints = ros::TransportHints() , |
|||
const ros::NodeHandle & | parameter_nh = ros::NodeHandle("~") , |
|||
const std::string & | parameter_name = "message_transport" | |||
) | [inline] |
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 "message_transport" in the node's local namespace. For consistency across ROS applications, the name of this parameter should not be changed without good reason.
default_transport | Preferred transport to use | |
ros_hints | Hints to pass through to ROS subscriptions | |
parameter_nh | Node handle to use when looking up the transport parameter. Defaults to the local namespace. | |
parameter_name | The name of the transport parameter |
Definition at line 28 of file transport_hints.h.
const ros::NodeHandle& message_transport::TransportHints::getParameterNH | ( | ) | const [inline] |
Definition at line 47 of file transport_hints.h.
const ros::TransportHints& message_transport::TransportHints::getRosHints | ( | ) | const [inline] |
Definition at line 42 of file transport_hints.h.
const std::string& message_transport::TransportHints::getTransport | ( | ) | const [inline] |
Definition at line 37 of file transport_hints.h.
ros::NodeHandle message_transport::TransportHints::parameter_nh_ [private] |
Definition at line 55 of file transport_hints.h.
ros::TransportHints message_transport::TransportHints::ros_hints_ [private] |
Definition at line 54 of file transport_hints.h.
std::string message_transport::TransportHints::transport_ [private] |
Definition at line 53 of file transport_hints.h.