#include <points2_publisher.h>

Public Member Functions | |
| Points2Publisher (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... | |
| void | publish (const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat, bool out1) |
| void | setOut1Alternate (bool alternate) |
| 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 | |
| Points2Publisher & | operator= (const Points2Publisher &) |
| Points2Publisher (const Points2Publisher &) | |
Private Attributes | |
| rcg::ImageList | disp_list |
| float | f |
| rcg::ImageList | left_list |
| ros::Publisher | pub |
| float | scale |
| uint32_t | seq |
| float | t |
| uint64_t | tolerance_ns |
Additional Inherited Members | |
Protected Attributes inherited from rc::GenICam2RosPublisher | |
| std::string | frame_id |
Definition at line 46 of file points2_publisher.h.
| rc::Points2Publisher::Points2Publisher | ( | 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. |
| frame_id | Parent frame id of points. |
Definition at line 42 of file points2_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 72 of file points2_publisher.cc.
| void rc::Points2Publisher::publish | ( | const rcg::Buffer * | buffer, |
| uint32_t | part, | ||
| uint64_t | pixelformat, | ||
| bool | out1 | ||
| ) |
Definition at line 77 of file points2_publisher.cc.
| void rc::Points2Publisher::setOut1Alternate | ( | bool | alternate | ) |
Definition at line 55 of file points2_publisher.cc.
|
overridevirtual |
Returns true if there are subscribers to the topic.
Implements rc::GenICam2RosPublisher.
Definition at line 67 of file points2_publisher.cc.
|
private |
Definition at line 73 of file points2_publisher.h.
|
private |
Definition at line 76 of file points2_publisher.h.
|
private |
Definition at line 72 of file points2_publisher.h.
|
private |
Definition at line 82 of file points2_publisher.h.
|
private |
Definition at line 78 of file points2_publisher.h.
|
private |
Definition at line 75 of file points2_publisher.h.
|
private |
Definition at line 77 of file points2_publisher.h.
|
private |
Definition at line 80 of file points2_publisher.h.