Manage image requests from one or more clients. More...
#include <publication_server.h>
Public Types | |
typedef boost::function< void(polled_camera::GetPolledImage::Request &, polled_camera::GetPolledImage::Response &, sensor_msgs::Image &, sensor_msgs::CameraInfo &)> | DriverCallback |
Public Member Functions | |
std::string | getService () const |
operator void * () const | |
bool | operator!= (const PublicationServer &rhs) const |
bool | operator< (const PublicationServer &rhs) const |
bool | operator== (const PublicationServer &rhs) const |
PublicationServer () | |
void | shutdown () |
Unadvertise the request service and shut down all published topics. More... | |
Private Member Functions | |
PublicationServer (const std::string &service, ros::NodeHandle &nh, const DriverCallback &cb, const ros::VoidPtr &tracked_object) | |
Private Attributes | |
boost::shared_ptr< Impl > | impl_ |
Friends | |
PublicationServer | advertise (ros::NodeHandle &, const std::string &, const DriverCallback &, const ros::VoidPtr &) |
Advertise a polled image service, version for arbitrary boost::function object. More... | |
Manage image requests from one or more clients.
Instances of polled_camera::PublicationServer should be created using one of the overloads of polled_camera::advertise(). You must specify a driver callback that populates the requested data:
Definition at line 80 of file publication_server.h.
typedef boost::function<void (polled_camera::GetPolledImage::Request&, polled_camera::GetPolledImage::Response&, sensor_msgs::Image&, sensor_msgs::CameraInfo&)> polled_camera::PublicationServer::DriverCallback |
Definition at line 86 of file publication_server.h.
|
inline |
Definition at line 88 of file publication_server.h.
|
private |
Definition at line 129 of file publication_server.cpp.
std::string polled_camera::PublicationServer::getService | ( | ) | const |
Definition at line 143 of file publication_server.cpp.
polled_camera::PublicationServer::operator void * | ( | ) | const |
Definition at line 149 of file publication_server.cpp.
|
inline |
Definition at line 100 of file publication_server.h.
|
inline |
Definition at line 98 of file publication_server.h.
|
inline |
Definition at line 99 of file publication_server.h.
void polled_camera::PublicationServer::shutdown | ( | ) |
Unadvertise the request service and shut down all published topics.
Definition at line 138 of file publication_server.cpp.
|
friend |
Advertise a polled image service, version for arbitrary boost::function object.
Definition at line 154 of file publication_server.cpp.
|
private |
Definition at line 106 of file publication_server.h.