#include <disparity_publisher.h>
Public Member Functions | |
DisparityPublisher (ros::NodeHandle &nh, std::string frame_id_prefix, double f, double t, double scale) | |
void | publish (const rcg::Buffer *buffer, uint64_t pixelformat) override |
void | setDisprange (int disprange) |
bool | used () override |
Private Member Functions | |
DisparityPublisher (const DisparityPublisher &) | |
DisparityPublisher & | operator= (const DisparityPublisher &) |
Private Attributes | |
int | disprange |
double | f |
ros::Publisher | pub |
float | scale |
uint32_t | seq |
double | t |
Definition at line 45 of file disparity_publisher.h.
rc::DisparityPublisher::DisparityPublisher | ( | ros::NodeHandle & | nh, |
std::string | frame_id_prefix, | ||
double | f, | ||
double | t, | ||
double | scale | ||
) |
Initialization of publisher.
nh | Node handle. |
f | Focal length, normalized to image width 1. |
t | Basline in m. |
scale | Factor for raw disparities. |
Definition at line 43 of file disparity_publisher.cc.
rc::DisparityPublisher::DisparityPublisher | ( | const DisparityPublisher & | ) | [private] |
DisparityPublisher& rc::DisparityPublisher::operator= | ( | const DisparityPublisher & | ) | [private] |
void rc::DisparityPublisher::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 67 of file disparity_publisher.cc.
void rc::DisparityPublisher::setDisprange | ( | int | disprange | ) |
Set the disparity range for scaling of images.
disprange | Disparity range for scaling. |
Definition at line 57 of file disparity_publisher.cc.
bool rc::DisparityPublisher::used | ( | ) | [override, virtual] |
Returns true if there are subscribers to the topic.
Implements rc::GenICam2RosPublisher.
Definition at line 62 of file disparity_publisher.cc.
int rc::DisparityPublisher::disprange [private] |
Definition at line 81 of file disparity_publisher.h.
double rc::DisparityPublisher::f [private] |
Definition at line 78 of file disparity_publisher.h.
ros::Publisher rc::DisparityPublisher::pub [private] |
Definition at line 83 of file disparity_publisher.h.
float rc::DisparityPublisher::scale [private] |
Definition at line 80 of file disparity_publisher.h.
uint32_t rc::DisparityPublisher::seq [private] |
Definition at line 77 of file disparity_publisher.h.
double rc::DisparityPublisher::t [private] |
Definition at line 79 of file disparity_publisher.h.