Public Member Functions | Private Member Functions | Private Attributes | List of all members
rc::DisparityPublisher Class Reference

#include <disparity_publisher.h>

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

Public Member Functions

 DisparityPublisher (ros::NodeHandle &nh, const std::string &frame_id_prefix, double f, double t, double scale)
 Initialization of publisher. More...
 
void publish (const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
 Offers a buffer for publication. More...
 
void setDepthRange (double _mindepth, double _maxdepth)
 Set the depth range of the disparity images. 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

 DisparityPublisher (const DisparityPublisher &)
 
DisparityPublisheroperator= (const DisparityPublisher &)
 

Private Attributes

double f
 
double maxdepth
 
double mindepth
 
ros::Publisher pub
 
float scale
 
uint32_t seq
 
double t
 

Additional Inherited Members

- Protected Attributes inherited from rc::GenICam2RosPublisher
std::string frame_id
 

Detailed Description

Definition at line 44 of file disparity_publisher.h.

Constructor & Destructor Documentation

rc::DisparityPublisher::DisparityPublisher ( ros::NodeHandle nh,
const 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 42 of file disparity_publisher.cc.

rc::DisparityPublisher::DisparityPublisher ( const DisparityPublisher )
private

Member Function Documentation

DisparityPublisher& rc::DisparityPublisher::operator= ( const DisparityPublisher )
private
void rc::DisparityPublisher::publish ( const rcg::Buffer buffer,
uint32_t  part,
uint64_t  pixelformat 
)
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.

Parameters
bufferBuffer with data to be published.
partPart index of image.
pixelformatThe pixelformat as given by buffer.getPixelFormat().

Implements rc::GenICam2RosPublisher.

Definition at line 67 of file disparity_publisher.cc.

void rc::DisparityPublisher::setDepthRange ( double  _mindepth,
double  _maxdepth 
)

Set the depth range of the disparity images.

Parameters
mindepthMinimum depth in m.
maxdepthMaximum depth in m.

Definition at line 56 of file disparity_publisher.cc.

bool rc::DisparityPublisher::used ( )
overridevirtual

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

double rc::DisparityPublisher::f
private

Definition at line 76 of file disparity_publisher.h.

double rc::DisparityPublisher::maxdepth
private

Definition at line 80 of file disparity_publisher.h.

double rc::DisparityPublisher::mindepth
private

Definition at line 79 of file disparity_publisher.h.

ros::Publisher rc::DisparityPublisher::pub
private

Definition at line 82 of file disparity_publisher.h.

float rc::DisparityPublisher::scale
private

Definition at line 78 of file disparity_publisher.h.

uint32_t rc::DisparityPublisher::seq
private

Definition at line 75 of file disparity_publisher.h.

double rc::DisparityPublisher::t
private

Definition at line 77 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 Sat Feb 13 2021 03:42:55