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

#include <points2_publisher.h>

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

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

Points2Publisheroperator= (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
 

Detailed Description

Definition at line 46 of file points2_publisher.h.

Constructor & Destructor Documentation

rc::Points2Publisher::Points2Publisher ( 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.
frame_idParent frame id of points.

Definition at line 42 of file points2_publisher.cc.

rc::Points2Publisher::Points2Publisher ( const Points2Publisher )
private

Member Function Documentation

Points2Publisher& rc::Points2Publisher::operator= ( const Points2Publisher )
private
void rc::Points2Publisher::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 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.

bool rc::Points2Publisher::used ( )
overridevirtual

Returns true if there are subscribers to the topic.

Returns
True if there are subscribers.

Implements rc::GenICam2RosPublisher.

Definition at line 67 of file points2_publisher.cc.

Member Data Documentation

rcg::ImageList rc::Points2Publisher::disp_list
private

Definition at line 73 of file points2_publisher.h.

float rc::Points2Publisher::f
private

Definition at line 76 of file points2_publisher.h.

rcg::ImageList rc::Points2Publisher::left_list
private

Definition at line 72 of file points2_publisher.h.

ros::Publisher rc::Points2Publisher::pub
private

Definition at line 82 of file points2_publisher.h.

float rc::Points2Publisher::scale
private

Definition at line 78 of file points2_publisher.h.

uint32_t rc::Points2Publisher::seq
private

Definition at line 75 of file points2_publisher.h.

float rc::Points2Publisher::t
private

Definition at line 77 of file points2_publisher.h.

uint64_t rc::Points2Publisher::tolerance_ns
private

Definition at line 80 of file points2_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 Wed Mar 20 2019 07:55:49