Class GenICam2RosPublisher
Defined in File genicam2ros_publisher.hpp
Inheritance Relationships
Derived Types
public rc::CameraInfoPublisher
(Class CameraInfoPublisher)public rc::CameraParamPublisher
(Class CameraParamPublisher)public rc::ConfidencePublisher
(Class ConfidencePublisher)public rc::DepthPublisher
(Class DepthPublisher)public rc::DisparityColorPublisher
(Class DisparityColorPublisher)public rc::DisparityPublisher
(Class DisparityPublisher)public rc::ErrorDepthPublisher
(Class ErrorDepthPublisher)public rc::ErrorDisparityPublisher
(Class ErrorDisparityPublisher)public rc::ImagePublisher
(Class ImagePublisher)public rc::Points2Publisher
(Class Points2Publisher)
Class Documentation
-
class GenICam2RosPublisher
Interface for all publishers relating to images, point clouds or other stereo-camera data
Subclassed by rc::CameraInfoPublisher, rc::CameraParamPublisher, rc::ConfidencePublisher, rc::DepthPublisher, rc::DisparityColorPublisher, rc::DisparityPublisher, rc::ErrorDepthPublisher, rc::ErrorDisparityPublisher, rc::ImagePublisher, rc::Points2Publisher
Public Functions
-
inline GenICam2RosPublisher(const std::string &_frame_id)
- Parameters:
frame_id_prefix – prefix for frame ids in published ros messages
-
inline virtual ~GenICam2RosPublisher()
Set nodemap to be used.
-
inline void clearNodemap()
Clear nodemap.
-
virtual void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) = 0
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.
- Parameters:
buffer – Buffer with data to be published. The buffer is already attached to the nodemap for accessing the chunk data.
part – Part index of image.
pixelformat – The pixelformat as given by buffer->getPixelFormat(part).
-
virtual bool used() = 0
Returns true if there are subscribers to the topic.
- Returns:
True if there are subscribers.
-
virtual void requiresComponents(int &components, bool &color) = 0
Adds components and if color images are required to the given values. Nothing will be changed if there are no subscribers, i.e. used() == false.
- Parameters:
components – Components Flags that will be updated according to the needs of this publisher.
color – Value that will be updated if this publisher needs color.
-
inline GenICam2RosPublisher(const std::string &_frame_id)