Namespaces | Classes | Typedefs | Functions
polled_camera Namespace Reference

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 Documentation

Definition at line 67 of file GetPolledImage.h.

Definition at line 70 of file GetPolledImage.h.

Definition at line 69 of file GetPolledImage.h.

Definition at line 105 of file GetPolledImage.h.

Definition at line 108 of file GetPolledImage.h.

Definition at line 107 of file GetPolledImage.h.


Function Documentation

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.

template<class T >
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.

template<class T >
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.



polled_camera
Author(s): Patrick Mihelich
autogenerated on Fri Jan 3 2014 11:24:21