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

#include <error_depth_publisher.h>

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

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 &)
 
ErrorDepthPublisheroperator= (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
 

Detailed Description

Definition at line 46 of file error_depth_publisher.h.

Constructor & Destructor Documentation

rc::ErrorDepthPublisher::ErrorDepthPublisher ( ros::NodeHandle nh,
const std::string &  frame_id_prefix,
double  f,
double  t,
double  scale 
)

Initialization of publisher for depth errors.

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

Definition at line 42 of file error_depth_publisher.cc.

rc::ErrorDepthPublisher::ErrorDepthPublisher ( const ErrorDepthPublisher )
private

Member Function Documentation

ErrorDepthPublisher& rc::ErrorDepthPublisher::operator= ( const ErrorDepthPublisher )
private
void rc::ErrorDepthPublisher::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 58 of file error_depth_publisher.cc.

bool rc::ErrorDepthPublisher::used ( )
overridevirtual

Returns true if there are subscribers to the topic.

Returns
True if there are subscribers.

Implements rc::GenICam2RosPublisher.

Definition at line 53 of file error_depth_publisher.cc.

Member Data Documentation

rcg::ImageList rc::ErrorDepthPublisher::disp_list
private

Definition at line 68 of file error_depth_publisher.h.

rcg::ImageList rc::ErrorDepthPublisher::err_list
private

Definition at line 69 of file error_depth_publisher.h.

float rc::ErrorDepthPublisher::f
private

Definition at line 72 of file error_depth_publisher.h.

ros::Publisher rc::ErrorDepthPublisher::pub
private

Definition at line 76 of file error_depth_publisher.h.

float rc::ErrorDepthPublisher::scale
private

Definition at line 74 of file error_depth_publisher.h.

uint32_t rc::ErrorDepthPublisher::seq
private

Definition at line 71 of file error_depth_publisher.h.

float rc::ErrorDepthPublisher::t
private

Definition at line 73 of file error_depth_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