Public Member Functions | Private Member Functions | Private Attributes
rc::DisparityPublisher Class Reference

#include <disparity_publisher.h>

Inheritance diagram for rc::DisparityPublisher:
Inheritance graph
[legend]

List of all members.

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 &)
DisparityPublisheroperator= (const DisparityPublisher &)

Private Attributes

int disprange
double f
ros::Publisher pub
float scale
uint32_t seq
double t

Detailed Description

Definition at line 45 of file disparity_publisher.h.


Constructor & Destructor Documentation

rc::DisparityPublisher::DisparityPublisher ( ros::NodeHandle nh,
std::string  frame_id_prefix,
double  f,
double  t,
double  scale 
)

Initialization of publisher.

Parameters:
nhNode handle.
fFocal length, normalized to image width 1.
tBasline in m.
scaleFactor for raw disparities.

Definition at line 43 of file disparity_publisher.cc.


Member Function Documentation

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.

Parameters:
bufferBuffer with data to be published.
pixelformatThe 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.

Parameters:
disprangeDisparity 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.

Returns:
True if there are subscribers.

Implements rc::GenICam2RosPublisher.

Definition at line 62 of file disparity_publisher.cc.


Member Data Documentation

Definition at line 81 of file disparity_publisher.h.

double rc::DisparityPublisher::f [private]

Definition at line 78 of file disparity_publisher.h.

Definition at line 83 of file disparity_publisher.h.

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.


The documentation for this class was generated from the following files:


rc_visard_driver
Author(s): Heiko Hirschmueller , Christian Emmerich , Felix Ruess
autogenerated on Thu Jun 6 2019 20:43:12