Classes | Namespaces | Macros | Functions
publication_server.h File Reference
#include <ros/ros.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/CameraInfo.h>
#include "polled_camera/GetPolledImage.h"
#include <ros/macros.h>
Include dependency graph for publication_server.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

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

Namespaces

 polled_camera
 

Macros

#define POLLED_CAMERA_DECL
 

Functions

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. More...
 
template<class T >
PublicationServer polled_camera::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. More...
 
template<class T >
PublicationServer polled_camera::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. More...
 

Macro Definition Documentation

#define POLLED_CAMERA_DECL

Definition at line 54 of file publication_server.h.



polled_camera
Author(s): Patrick Mihelich
autogenerated on Sat Apr 4 2020 03:15:07