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. | |
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. |
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:
void callback(polled_camera::GetPolledImage::Request& req, polled_camera::GetPolledImage::Response& rsp, sensor_msgs::Image& image, sensor_msgs::CameraInfo& info) { // Capture an image and fill in the Image and CameraInfo messages here. // On success, set rsp.success = true. rsp.timestamp will be filled in // automatically. // On failure, set rsp.success = false and fill rsp.status_message with an // informative error message. }
Definition at line 66 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 72 of file publication_server.h.
polled_camera::PublicationServer::PublicationServer | ( | ) | [inline] |
Definition at line 74 of file publication_server.h.
polled_camera::PublicationServer::PublicationServer | ( | const std::string & | service, |
ros::NodeHandle & | nh, | ||
const DriverCallback & | cb, | ||
const ros::VoidPtr & | tracked_object | ||
) | [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.
bool polled_camera::PublicationServer::operator!= | ( | const PublicationServer & | rhs | ) | const [inline] |
Definition at line 86 of file publication_server.h.
bool polled_camera::PublicationServer::operator< | ( | const PublicationServer & | rhs | ) | const [inline] |
Definition at line 84 of file publication_server.h.
bool polled_camera::PublicationServer::operator== | ( | const PublicationServer & | rhs | ) | const [inline] |
Definition at line 85 of file publication_server.h.
Unadvertise the request service and shut down all published topics.
Definition at line 138 of file publication_server.cpp.
PublicationServer advertise | ( | ros::NodeHandle & | nh, |
const std::string & | service, | ||
const DriverCallback & | cb, | ||
const ros::VoidPtr & | tracked_object = ros::VoidPtr() |
||
) | [friend] |
Advertise a polled image service, version for arbitrary boost::function object.
boost::shared_ptr<Impl> polled_camera::PublicationServer::impl_ [private] |
Definition at line 92 of file publication_server.h.