transport_hints.h
Go to the documentation of this file.
00001 #ifndef MESSAGE_TRANSPORT_TRANSPORT_HINTS_H
00002 #define MESSAGE_TRANSPORT_TRANSPORT_HINTS_H
00003 
00004 #include <ros/ros.h>
00005 
00006 namespace message_transport {
00007 
00011 class TransportHints
00012 {
00013 public:
00028   TransportHints(const std::string& default_transport = "raw",
00029                  const ros::TransportHints& ros_hints = ros::TransportHints(),
00030                  const ros::NodeHandle& parameter_nh = ros::NodeHandle("~"),
00031                  const std::string& parameter_name = "message_transport")
00032     : ros_hints_(ros_hints), parameter_nh_(parameter_nh)
00033   {
00034     parameter_nh_.param(parameter_name, transport_, default_transport);
00035   }
00036 
00037   const std::string& getTransport() const
00038   {
00039     return transport_;
00040   }
00041 
00042   const ros::TransportHints& getRosHints() const
00043   {
00044     return ros_hints_;
00045   }
00046 
00047   const ros::NodeHandle& getParameterNH() const
00048   {
00049     return parameter_nh_;
00050   }
00051   
00052 private:
00053   std::string transport_;
00054   ros::TransportHints ros_hints_;
00055   ros::NodeHandle parameter_nh_;
00056 };
00057 
00058 } //namespace message_transport
00059 
00060 #endif


message_transport_common
Author(s): Cedric Pradalier
autogenerated on Sun Oct 5 2014 23:48:49