Classes | Functions
polled_camera Namespace Reference

Classes

class  PublicationServer
 Manage image requests from one or more clients. More...

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.

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 154 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 112 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 125 of file publication_server.h.



polled_camera
Author(s): Patrick Mihelich
autogenerated on Tue Jun 6 2017 02:33:47