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, std::function< void()> &sub_changed)
 
void publish (const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
 Offers a buffer for publication. More...
 
void requiresComponents (int &components, bool &color) override
 Adds components and if color images are required to the given values. More...
 
bool used () override
 Returns true if there are subscribers to the topic. More...
 
- Public Member Functions inherited from rc::GenICam2RosPublisher
void clearNodemap ()
 Clear nodemap. More...
 
 GenICam2RosPublisher (const std::string &_frame_id)
 
void setNodemap (const std::shared_ptr< GenApi::CNodeMapRef > &_nodemap)
 Set nodemap to be used. More...
 
void subChanged (const ros::SingleSubscriberPublisher &pub)
 Called by publisher if subscription changed. More...
 
void subChangedIt (const image_transport::SingleSubscriberPublisher &pub)
 Called by publisher if subscription changed. More...
 
virtual ~GenICam2RosPublisher ()
 

Private Member Functions

 ErrorDepthPublisher (const ErrorDepthPublisher &)
 
ErrorDepthPublisheroperator= (const ErrorDepthPublisher &)
 

Private Attributes

rcg::ImageList disp_list
 
rcg::ImageList err_list
 
float f
 
float invalid
 
ros::Publisher pub
 
float scale
 
float t
 

Additional Inherited Members

- Static Public Attributes inherited from rc::GenICam2RosPublisher
const static int ComponentConfidence = 8
 
const static int ComponentDisparity = 4
 
const static int ComponentError = 16
 
const static int ComponentIntensity = 1
 
const static int ComponentIntensityCombined = 2
 
- Protected Attributes inherited from rc::GenICam2RosPublisher
std::string frame_id
 
std::shared_ptr< GenApi::CNodeMapRef > nodemap
 
std::function< void()> sub_callback
 

Detailed Description

Definition at line 46 of file error_depth_publisher.h.

Constructor & Destructor Documentation

◆ ErrorDepthPublisher() [1/2]

rc::ErrorDepthPublisher::ErrorDepthPublisher ( ros::NodeHandle nh,
const std::string &  frame_id,
std::function< void()> &  sub_changed 
)

Definition at line 43 of file error_depth_publisher.cpp.

◆ ErrorDepthPublisher() [2/2]

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

Member Function Documentation

◆ operator=()

ErrorDepthPublisher& rc::ErrorDepthPublisher::operator= ( const ErrorDepthPublisher )
private

◆ publish()

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. The buffer is already attached to the nodemap for accessing the chunk data.
partPart index of image.
pixelformatThe pixelformat as given by buffer->getPixelFormat(part).

Implements rc::GenICam2RosPublisher.

Definition at line 70 of file error_depth_publisher.cpp.

◆ requiresComponents()

void rc::ErrorDepthPublisher::requiresComponents ( int &  components,
bool &  color 
)
overridevirtual

Adds components and if color images are required to the given values.

Nothing will be changed if there are no subscribers, i.e. used() == false.

Parameters
componentsComponents Flags that will be updated according to the needs of this publisher.
colorValue that will be updated if this publisher needs color.

Implements rc::GenICam2RosPublisher.

Definition at line 62 of file error_depth_publisher.cpp.

◆ used()

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 57 of file error_depth_publisher.cpp.

Member Data Documentation

◆ disp_list

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

Definition at line 60 of file error_depth_publisher.h.

◆ err_list

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

Definition at line 61 of file error_depth_publisher.h.

◆ f

float rc::ErrorDepthPublisher::f
private

Definition at line 63 of file error_depth_publisher.h.

◆ invalid

float rc::ErrorDepthPublisher::invalid
private

Definition at line 64 of file error_depth_publisher.h.

◆ pub

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

Definition at line 67 of file error_depth_publisher.h.

◆ scale

float rc::ErrorDepthPublisher::scale
private

Definition at line 65 of file error_depth_publisher.h.

◆ t

float rc::ErrorDepthPublisher::t
private

Definition at line 63 of file error_depth_publisher.h.


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


rc_genicam_driver
Author(s): Heiko Hirschmueller , Felix Ruess
autogenerated on Sat Oct 26 2024 02:04:09