Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef POLLED_CAMERA_PUBLICATION_SERVER_H
00036 #define POLLED_CAMERA_PUBLICATION_SERVER_H
00037
00038 #include <ros/ros.h>
00039 #include <sensor_msgs/Image.h>
00040 #include <sensor_msgs/CameraInfo.h>
00041 #include "polled_camera/GetPolledImage.h"
00042
00043 namespace polled_camera {
00044
00066 class PublicationServer
00067 {
00068 public:
00069 typedef boost::function<void (polled_camera::GetPolledImage::Request&,
00070 polled_camera::GetPolledImage::Response&,
00071 sensor_msgs::Image&,
00072 sensor_msgs::CameraInfo&)> DriverCallback;
00073
00074 PublicationServer() {}
00075
00079 void shutdown();
00080
00081 std::string getService() const;
00082
00083 operator void*() const;
00084 bool operator< (const PublicationServer& rhs) const { return impl_ < rhs.impl_; }
00085 bool operator==(const PublicationServer& rhs) const { return impl_ == rhs.impl_; }
00086 bool operator!=(const PublicationServer& rhs) const { return impl_ != rhs.impl_; }
00087
00088 private:
00089 PublicationServer(const std::string& service, ros::NodeHandle& nh,
00090 const DriverCallback& cb, const ros::VoidPtr& tracked_object);
00091
00092 class Impl;
00093
00094 boost::shared_ptr<Impl> impl_;
00095
00096 friend
00097 PublicationServer advertise(ros::NodeHandle&, const std::string&, const DriverCallback&,
00098 const ros::VoidPtr&);
00099 };
00100
00104 PublicationServer advertise(ros::NodeHandle& nh, const std::string& service,
00105 const PublicationServer::DriverCallback& cb,
00106 const ros::VoidPtr& tracked_object = ros::VoidPtr());
00107
00111 template<class T>
00112 PublicationServer advertise(ros::NodeHandle& nh, const std::string& service,
00113 void(T::*fp)(polled_camera::GetPolledImage::Request&,
00114 polled_camera::GetPolledImage::Response&,
00115 sensor_msgs::Image&, sensor_msgs::CameraInfo&),
00116 T* obj)
00117 {
00118 return advertise(nh, service, boost::bind(fp, obj, _1, _2, _3, _4));
00119 }
00120
00124 template<class T>
00125 PublicationServer advertise(ros::NodeHandle& nh, const std::string& service,
00126 void(T::*fp)(polled_camera::GetPolledImage::Request&,
00127 polled_camera::GetPolledImage::Response&,
00128 sensor_msgs::Image&, sensor_msgs::CameraInfo&),
00129 const boost::shared_ptr<T>& obj)
00130 {
00131 return advertise(nh, service, boost::bind(fp, obj.get(), _1, _2, _3, _4), obj);
00132 }
00133
00134 }
00135
00136 #endif