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" 47 #ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries 48 #ifdef polled_camera_EXPORTS // we are building a shared lib/dll 49 #define POLLED_CAMERA_DECL ROS_HELPER_EXPORT 50 #else // we are using shared lib/dll 51 #define POLLED_CAMERA_DECL ROS_HELPER_IMPORT 53 #else // ros is being built around static libraries 54 #define POLLED_CAMERA_DECL 83 typedef boost::function<void (polled_camera::GetPolledImage::Request&,
84 polled_camera::GetPolledImage::Response&,
95 std::string getService()
const;
97 operator void*()
const;
104 const DriverCallback& cb,
const ros::VoidPtr& tracked_object);
127 void(T::*fp)(polled_camera::GetPolledImage::Request&,
128 polled_camera::GetPolledImage::Response&,
129 sensor_msgs::Image&, sensor_msgs::CameraInfo&),
132 return advertise(nh, service, boost::bind(fp, obj, _1, _2, _3, _4));
140 void(T::*fp)(polled_camera::GetPolledImage::Request&,
141 polled_camera::GetPolledImage::Response&,
142 sensor_msgs::Image&, sensor_msgs::CameraInfo&),
145 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
PublicationServer advertise(ros::NodeHandle &nh, const std::string &service, const PublicationServer::DriverCallback &cb, const ros::VoidPtr &tracked_object=ros::VoidPtr())
Advertise a polled image service, version for arbitrary boost::function object.
Manage image requests from one or more clients.
#define POLLED_CAMERA_DECL
boost::shared_ptr< Impl > impl_
boost::function< void(polled_camera::GetPolledImage::Request &, polled_camera::GetPolledImage::Response &, sensor_msgs::Image &, sensor_msgs::CameraInfo &)> DriverCallback