35 #ifndef IMAGE_TRANSPORT_IMAGE_TRANSPORT_H 36 #define IMAGE_TRANSPORT_IMAGE_TRANSPORT_H 61 Publisher advertise(
const std::string& base_topic, uint32_t queue_size,
bool latch =
false);
75 const boost::function<
void(
const sensor_msgs::ImageConstPtr&)>& callback,
83 void(*fp)(
const sensor_msgs::ImageConstPtr&),
87 boost::function<
void(
const sensor_msgs::ImageConstPtr&)>(fp),
96 void(T::*fp)(
const sensor_msgs::ImageConstPtr&), T* obj,
107 void(T::*fp)(
const sensor_msgs::ImageConstPtr&),
111 return subscribe(base_topic, queue_size, boost::bind(fp, obj.get(), _1), obj, transport_hints);
146 void(*fp)(
const sensor_msgs::ImageConstPtr&,
147 const sensor_msgs::CameraInfoConstPtr&),
160 void(T::*fp)(
const sensor_msgs::ImageConstPtr&,
161 const sensor_msgs::CameraInfoConstPtr&), T* obj,
174 void(T::*fp)(
const sensor_msgs::ImageConstPtr&,
175 const sensor_msgs::CameraInfoConstPtr&),
179 return subscribeCamera(base_topic, queue_size, boost::bind(fp, obj.get(), _1, _2), obj,
Manages advertisements of multiple transport options on an Image topic.
std::vector< std::string > getLoadableTransports() const
Returns the names of all transports that are loadable in the system.
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
Subscribe to an image topic, version for arbitrary boost::function object.
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
ImageTransport(const ros::NodeHandle &nh)
CameraSubscriber subscribeCamera(const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &), T *obj, const TransportHints &transport_hints=TransportHints())
Subscribe to a synchronized image & camera info topic pair, version for class member function with ba...
CameraSubscriber subscribeCamera(const std::string &base_topic, uint32_t queue_size, const CameraSubscriber::Callback &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
Subscribe to a synchronized image & camera info topic pair, version for arbitrary boost::function obj...
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
Advertise an image topic, simple version.
Manages advertisements for publishing camera images.
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const sensor_msgs::ImageConstPtr &), T *obj, const TransportHints &transport_hints=TransportHints())
Subscribe to an image topic, version for class member function with bare pointer. ...
Manages a subscription callback on a specific topic that can be interpreted as an Image topic...
Manages a subscription callback on synchronized Image and CameraInfo topics.
boost::shared_ptr< Impl > ImplPtr
boost::weak_ptr< Impl > ImplWPtr
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
Advertise a synchronized camera raw image + info topic pair, simple version.
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, void(*fp)(const sensor_msgs::ImageConstPtr &), const TransportHints &transport_hints=TransportHints())
Subscribe to an image topic, version for bare function.
CameraSubscriber subscribeCamera(const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &), const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
Subscribe to a synchronized image & camera info topic pair, version for class member function with sh...
std::vector< std::string > getDeclaredTransports() const
Returns the names of all transports declared in the system. Declared transports are not necessarily b...
CameraSubscriber subscribeCamera(const std::string &base_topic, uint32_t queue_size, void(*fp)(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &), const TransportHints &transport_hints=TransportHints())
Subscribe to a synchronized image & camera info topic pair, version for bare function.
boost::function< void(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &)> Callback
Stores transport settings for an image topic subscription.
Advertise and subscribe to image topics.
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const sensor_msgs::ImageConstPtr &), const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
Subscribe to an image topic, version for class member function with shared_ptr.