#include <error_depth_publisher.h>
Public Member Functions | |
ErrorDepthPublisher (ros::NodeHandle &nh, const std::string &frame_id_prefix, double f, double t, double scale) | |
Initialization of publisher for depth errors. More... | |
void | publish (const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override |
Offers a buffer for publication. More... | |
bool | used () override |
Returns true if there are subscribers to the topic. More... | |
Public Member Functions inherited from rc::GenICam2RosPublisher | |
GenICam2RosPublisher (const std::string &frame_id_prefix) | |
virtual | ~GenICam2RosPublisher () |
Private Member Functions | |
ErrorDepthPublisher (const ErrorDepthPublisher &) | |
ErrorDepthPublisher & | operator= (const ErrorDepthPublisher &) |
Private Attributes | |
rcg::ImageList | disp_list |
rcg::ImageList | err_list |
float | f |
ros::Publisher | pub |
float | scale |
uint32_t | seq |
float | t |
Additional Inherited Members | |
Protected Attributes inherited from rc::GenICam2RosPublisher | |
std::string | frame_id |
Definition at line 46 of file error_depth_publisher.h.
rc::ErrorDepthPublisher::ErrorDepthPublisher | ( | ros::NodeHandle & | nh, |
const std::string & | frame_id_prefix, | ||
double | f, | ||
double | t, | ||
double | scale | ||
) |
Initialization of publisher for depth errors.
nh | Node handle. |
f | Focal length, normalized to image width of 1. |
t | Basline in m. |
scale | Factor for raw disparities. |
Definition at line 42 of file error_depth_publisher.cc.
|
private |
|
private |
|
overridevirtual |
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(). |
Implements rc::GenICam2RosPublisher.
Definition at line 58 of file error_depth_publisher.cc.
|
overridevirtual |
Returns true if there are subscribers to the topic.
Implements rc::GenICam2RosPublisher.
Definition at line 53 of file error_depth_publisher.cc.
|
private |
Definition at line 68 of file error_depth_publisher.h.
|
private |
Definition at line 69 of file error_depth_publisher.h.
|
private |
Definition at line 72 of file error_depth_publisher.h.
|
private |
Definition at line 76 of file error_depth_publisher.h.
|
private |
Definition at line 74 of file error_depth_publisher.h.
|
private |
Definition at line 71 of file error_depth_publisher.h.
|
private |
Definition at line 73 of file error_depth_publisher.h.