35 #ifndef POLLED_CAMERA_PUBLICATION_SERVER_H 36 #define POLLED_CAMERA_PUBLICATION_SERVER_H 39 #include <sensor_msgs/Image.h> 40 #include <sensor_msgs/CameraInfo.h> 41 #include "polled_camera/GetPolledImage.h" 69 typedef boost::function<void (polled_camera::GetPolledImage::Request&,
70 polled_camera::GetPolledImage::Response&,
83 operator void*()
const;
90 const DriverCallback& cb,
const ros::VoidPtr& tracked_object);
113 void(T::*fp)(polled_camera::GetPolledImage::Request&,
114 polled_camera::GetPolledImage::Response&,
115 sensor_msgs::Image&, sensor_msgs::CameraInfo&),
118 return advertise(nh, service, boost::bind(fp, obj, _1, _2, _3, _4));
126 void(T::*fp)(polled_camera::GetPolledImage::Request&,
127 polled_camera::GetPolledImage::Response&,
128 sensor_msgs::Image&, sensor_msgs::CameraInfo&),
131 return advertise(nh, service, boost::bind(fp, obj.get(), _1, _2, _3, _4), obj);
bool operator!=(const PublicationServer &rhs) const
bool operator==(const PublicationServer &rhs) const
Manage image requests from one or more clients.
std::string getService() const
friend PublicationServer advertise(ros::NodeHandle &, const std::string &, const DriverCallback &, const ros::VoidPtr &)
Advertise a polled image service, version for arbitrary boost::function object.
void shutdown()
Unadvertise the request service and shut down all published topics.
boost::shared_ptr< Impl > impl_
bool operator<(const PublicationServer &rhs) const
boost::function< void(polled_camera::GetPolledImage::Request &, polled_camera::GetPolledImage::Response &, sensor_msgs::Image &, sensor_msgs::CameraInfo &)> DriverCallback