35 #ifndef IMAGE_TRANSPORT_IMAGE_TRANSPORT_H
36 #define IMAGE_TRANSPORT_IMAGE_TRANSPORT_H
62 Publisher advertise(
const std::string& base_topic, uint32_t queue_size,
bool latch =
false);
67 Publisher advertise(
const std::string& base_topic, uint32_t queue_size,
75 Subscriber subscribe(
const std::string& base_topic, uint32_t queue_size,
76 const boost::function<
void(
const sensor_msgs::ImageConstPtr&)>& callback,
78 const TransportHints& transport_hints = TransportHints());
83 Subscriber subscribe(
const std::string& base_topic, uint32_t queue_size,
84 void(*fp)(
const sensor_msgs::ImageConstPtr&),
87 return subscribe(base_topic, queue_size,
88 boost::function<
void(
const sensor_msgs::ImageConstPtr&)>(fp),
96 Subscriber subscribe(
const std::string& base_topic, uint32_t queue_size,
97 void(T::*fp)(
const sensor_msgs::ImageConstPtr&), T* obj,
100 return subscribe(base_topic, queue_size, boost::bind(fp, obj, boost::placeholders::_1),
ros::VoidPtr(), transport_hints);
107 Subscriber subscribe(
const std::string& base_topic, uint32_t queue_size,
108 void(T::*fp)(
const sensor_msgs::ImageConstPtr&),
110 const TransportHints& transport_hints = TransportHints())
112 return subscribe(base_topic, queue_size, boost::bind(fp, obj.get(), boost::placeholders::_1), obj, transport_hints);
118 CameraPublisher advertiseCamera(
const std::string& base_topic, uint32_t queue_size,
bool latch =
false);
124 CameraPublisher advertiseCamera(
const std::string& base_topic, uint32_t queue_size,
138 CameraSubscriber subscribeCamera(
const std::string& base_topic, uint32_t queue_size,
141 const TransportHints& transport_hints = TransportHints());
146 CameraSubscriber subscribeCamera(
const std::string& base_topic, uint32_t queue_size,
147 void(*fp)(
const sensor_msgs::ImageConstPtr&,
148 const sensor_msgs::CameraInfoConstPtr&),
161 void(T::*fp)(
const sensor_msgs::ImageConstPtr&,
162 const sensor_msgs::CameraInfoConstPtr&), T* obj,
165 return subscribeCamera(base_topic, queue_size, boost::bind(fp, obj, boost::placeholders::_1, boost::placeholders::_2),
ros::VoidPtr(),
174 CameraSubscriber subscribeCamera(
const std::string& base_topic, uint32_t queue_size,
175 void(T::*fp)(
const sensor_msgs::ImageConstPtr&,
176 const sensor_msgs::CameraInfoConstPtr&),
180 return subscribeCamera(base_topic, queue_size, boost::bind(fp, obj.get(), boost::placeholders::_1, boost::placeholders::_2), obj,
188 std::vector<std::string> getDeclaredTransports()
const;
193 std::vector<std::string> getLoadableTransports()
const;
198 typedef boost::weak_ptr<Impl> ImplWPtr;