Namespaces | |
namespace | srv |
Classes | |
struct | GetPolledImage |
struct | GetPolledImageRequest_ |
struct | GetPolledImageResponse_ |
class | PublicationServer |
Manage image requests from one or more clients. More... | |
Typedefs | |
typedef ::polled_camera::GetPolledImageRequest_ < std::allocator< void > > | GetPolledImageRequest |
typedef boost::shared_ptr < ::polled_camera::GetPolledImageRequest const > | GetPolledImageRequestConstPtr |
typedef boost::shared_ptr < ::polled_camera::GetPolledImageRequest > | GetPolledImageRequestPtr |
typedef ::polled_camera::GetPolledImageResponse_ < std::allocator< void > > | GetPolledImageResponse |
typedef boost::shared_ptr < ::polled_camera::GetPolledImageResponse const > | GetPolledImageResponseConstPtr |
typedef boost::shared_ptr < ::polled_camera::GetPolledImageResponse > | GetPolledImageResponsePtr |
Functions | |
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. | |
template<class T > | |
PublicationServer | advertise (ros::NodeHandle &nh, const std::string &service, void(T::*fp)(polled_camera::GetPolledImage::Request &, polled_camera::GetPolledImage::Response &, sensor_msgs::Image &, sensor_msgs::CameraInfo &), T *obj) |
Advertise a polled image service, version for class member function with bare pointer. | |
template<class T > | |
PublicationServer | advertise (ros::NodeHandle &nh, const std::string &service, void(T::*fp)(polled_camera::GetPolledImage::Request &, polled_camera::GetPolledImage::Response &, sensor_msgs::Image &, sensor_msgs::CameraInfo &), const boost::shared_ptr< T > &obj) |
Advertise a polled image service, version for class member function with bare pointer. |
typedef ::polled_camera::GetPolledImageRequest_<std::allocator<void> > polled_camera::GetPolledImageRequest |
Definition at line 67 of file GetPolledImage.h.
typedef boost::shared_ptr< ::polled_camera::GetPolledImageRequest const> polled_camera::GetPolledImageRequestConstPtr |
Definition at line 70 of file GetPolledImage.h.
typedef boost::shared_ptr< ::polled_camera::GetPolledImageRequest> polled_camera::GetPolledImageRequestPtr |
Definition at line 69 of file GetPolledImage.h.
typedef ::polled_camera::GetPolledImageResponse_<std::allocator<void> > polled_camera::GetPolledImageResponse |
Definition at line 105 of file GetPolledImage.h.
typedef boost::shared_ptr< ::polled_camera::GetPolledImageResponse const> polled_camera::GetPolledImageResponseConstPtr |
Definition at line 108 of file GetPolledImage.h.
typedef boost::shared_ptr< ::polled_camera::GetPolledImageResponse> polled_camera::GetPolledImageResponsePtr |
Definition at line 107 of file GetPolledImage.h.
PublicationServer polled_camera::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.
Definition at line 120 of file publication_server.cpp.
PublicationServer polled_camera::advertise | ( | ros::NodeHandle & | nh, |
const std::string & | service, | ||
void(T::*)(polled_camera::GetPolledImage::Request &, polled_camera::GetPolledImage::Response &, sensor_msgs::Image &, sensor_msgs::CameraInfo &) | fp, | ||
T * | obj | ||
) |
Advertise a polled image service, version for class member function with bare pointer.
Definition at line 78 of file publication_server.h.
PublicationServer polled_camera::advertise | ( | ros::NodeHandle & | nh, |
const std::string & | service, | ||
void(T::*)(polled_camera::GetPolledImage::Request &, polled_camera::GetPolledImage::Response &, sensor_msgs::Image &, sensor_msgs::CameraInfo &) | fp, | ||
const boost::shared_ptr< T > & | obj | ||
) |
Advertise a polled image service, version for class member function with bare pointer.
Definition at line 91 of file publication_server.h.