Stores transport settings for an image topic subscription.
More...
#include <transport_hints.h>
Stores transport settings for an image topic subscription.
Definition at line 45 of file transport_hints.h.
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_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 62 of file transport_hints.h.
const ros::NodeHandle& image_transport::TransportHints::getParameterNH |
( |
| ) |
const |
|
inline |
const std::string& image_transport::TransportHints::getTransport |
( |
| ) |
const |
|
inline |
std::string image_transport::TransportHints::transport_ |
|
private |
The documentation for this class was generated from the following file: