#include <error_disparity_publisher.h>

| Public Member Functions | |
| ErrorDisparityPublisher (ros::NodeHandle &nh, std::string frame_id_prefix, double scale) | |
| void | publish (const rcg::Buffer *buffer, uint64_t pixelformat) override | 
| bool | used () override | 
| Private Member Functions | |
| ErrorDisparityPublisher (const ErrorDisparityPublisher &) | |
| ErrorDisparityPublisher & | operator= (const ErrorDisparityPublisher &) | 
| Private Attributes | |
| ros::Publisher | pub | 
| float | scale | 
| uint32_t | seq | 
Definition at line 47 of file error_disparity_publisher.h.
| rc::ErrorDisparityPublisher::ErrorDisparityPublisher | ( | ros::NodeHandle & | nh, | 
| std::string | frame_id_prefix, | ||
| double | scale | ||
| ) | 
Initialization of publisher for disparity errors.
| nh | Node handle. | 
| scale | Factor for raw disparities. | 
Definition at line 43 of file error_disparity_publisher.cc.
| rc::ErrorDisparityPublisher::ErrorDisparityPublisher | ( | const ErrorDisparityPublisher & | ) |  [private] | 
| ErrorDisparityPublisher& rc::ErrorDisparityPublisher::operator= | ( | const ErrorDisparityPublisher & | ) |  [private] | 
| void rc::ErrorDisparityPublisher::publish | ( | const rcg::Buffer * | buffer, | 
| uint64_t | pixelformat | ||
| ) |  [override, 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. | 
| pixelformat | The pixelformat as given by buffer.getPixelFormat(). | 
Implements rc::GenICam2RosPublisher.
Definition at line 58 of file error_disparity_publisher.cc.
| bool rc::ErrorDisparityPublisher::used | ( | ) |  [override, virtual] | 
Returns true if there are subscribers to the topic.
Implements rc::GenICam2RosPublisher.
Definition at line 53 of file error_disparity_publisher.cc.
Definition at line 72 of file error_disparity_publisher.h.
| float rc::ErrorDisparityPublisher::scale  [private] | 
Definition at line 70 of file error_disparity_publisher.h.
| uint32_t rc::ErrorDisparityPublisher::seq  [private] | 
Definition at line 69 of file error_disparity_publisher.h.