Interface for all publishers relating to images, point clouds or other stereo-camera data. More...
#include <genicam2ros_publisher.h>

Public Member Functions | |
| GenICam2RosPublisher (const std::string &frame_id_prefix) | |
| virtual void | publish (const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat)=0 |
| Offers a buffer for publication. More... | |
| virtual bool | used ()=0 |
| Returns true if there are subscribers to the topic. More... | |
| virtual | ~GenICam2RosPublisher () |
Protected Attributes | |
| std::string | frame_id |
Private Member Functions | |
| GenICam2RosPublisher & | operator= (const GenICam2RosPublisher &) |
Interface for all publishers relating to images, point clouds or other stereo-camera data.
Definition at line 47 of file genicam2ros_publisher.h.
|
inline |
| frame_id_prefix | prefix for frame ids in published ros messages |
Definition at line 53 of file genicam2ros_publisher.h.
|
inlinevirtual |
Definition at line 57 of file genicam2ros_publisher.h.
|
private |
|
pure virtual |
Offers a buffer for publication.
It depends on the the kind of buffer data and the implementation and configuration of the sub-class if the data is published.
| buffer | Buffer with data to be published. |
| part | Part index of image. |
| pixelformat | The pixelformat as given by buffer.getPixelFormat(). |
Implemented in rc::ImagePublisher, rc::DisparityColorPublisher, rc::DisparityPublisher, rc::Points2Publisher, rc::ErrorDepthPublisher, rc::CameraInfoPublisher, rc::DepthPublisher, rc::ErrorDisparityPublisher, and rc::ConfidencePublisher.
|
pure virtual |
Returns true if there are subscribers to the topic.
Implemented in rc::DisparityColorPublisher, rc::DisparityPublisher, rc::Points2Publisher, rc::ImagePublisher, rc::ErrorDepthPublisher, rc::CameraInfoPublisher, rc::DepthPublisher, rc::ErrorDisparityPublisher, and rc::ConfidencePublisher.
|
protected |
Definition at line 81 of file genicam2ros_publisher.h.