Public Member Functions | Private Attributes | List of all members
image_transport::TransportHints Class Reference

Stores transport settings for an image topic subscription. More...

#include <transport_hints.h>

Public Member Functions

const ros::NodeHandlegetParameterNH () const
 
const ros::TransportHintsgetRosHints () const
 
const std::string & getTransport () const
 
 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="image_transport")
 Constructor. More...
 

Private Attributes

ros::NodeHandle parameter_nh_
 
ros::TransportHints ros_hints_
 
std::string transport_
 

Detailed Description

Stores transport settings for an image topic subscription.

Definition at line 77 of file transport_hints.h.

Constructor & Destructor Documentation

◆ TransportHints()

image_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 = "image_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 "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
default_transportPreferred transport to use
ros_hintsHints to pass through to ROS subscriptions
parameter_nhNode handle to use when looking up the transport parameter. Defaults to the local namespace.
parameter_nameThe name of the transport parameter

Definition at line 126 of file transport_hints.h.

Member Function Documentation

◆ getParameterNH()

const ros::NodeHandle& image_transport::TransportHints::getParameterNH ( ) const
inline

Definition at line 145 of file transport_hints.h.

◆ getRosHints()

const ros::TransportHints& image_transport::TransportHints::getRosHints ( ) const
inline

Definition at line 140 of file transport_hints.h.

◆ getTransport()

const std::string& image_transport::TransportHints::getTransport ( ) const
inline

Definition at line 135 of file transport_hints.h.

Member Data Documentation

◆ parameter_nh_

ros::NodeHandle image_transport::TransportHints::parameter_nh_
private

Definition at line 153 of file transport_hints.h.

◆ ros_hints_

ros::TransportHints image_transport::TransportHints::ros_hints_
private

Definition at line 152 of file transport_hints.h.

◆ transport_

std::string image_transport::TransportHints::transport_
private

Definition at line 151 of file transport_hints.h.


The documentation for this class was generated from the following file:


image_transport
Author(s): Patrick Mihelich
autogenerated on Sat Jan 20 2024 03:14:50