Public Member Functions | Private Member Functions | Private Attributes | List of all members
CompoundPublisher Class Reference

A compound publisher for the driver's topics. More...

#include <compound_publisher.h>

Public Member Functions

 CompoundPublisher ()
 
void publish (const std_msgs::Header &header, visionary::SafeVisionaryData &frame_data)
 Publish once with all registered publishers. More...
 
virtual ~CompoundPublisher ()
 

Private Member Functions

void publishCameraInfo (const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
 Publishes the camera information of the sensor. More...
 
void publishDepthImage (const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
 Publishes the raw depth image. More...
 
void publishDeviceStatus (const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
 Publishes the device status. More...
 
void publishFieldInformation (const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
 Publishes the evaluation of the configured safety fields. More...
 
void publishIMUData (const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
 Publishes the values of the IMU. More...
 
void publishIntensityImage (const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
 Publishes the raw intensity image. More...
 
void publishIOs (const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
 Publishes the state of the IO ports. More...
 
void publishPointCloud (const std_msgs::Header &header, visionary::SafeVisionaryData &frame_data)
 Publishes the generated 3D Pointcloud. More...
 
void publishROI (const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
 Publishes the regions of interest. More...
 
void publishStateMap (const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
 Publishes the raw state map of each pixel. More...
 
sensor_msgs::ImagePtr Vec16ToImage (const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data, std::vector< uint16_t > vec)
 Creates an image from a data vector. More...
 
sensor_msgs::ImagePtr Vec8ToImage (const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data, std::vector< uint8_t > vec)
 Creates an image from a data vector. More...
 

Private Attributes

ros::Publisher camera_info_pub_
 
image_transport::Publisher depth_pub_
 
ros::Publisher device_status_pub_
 
ros::Publisher field_pub_
 
ros::Publisher imu_pub_
 
image_transport::Publisher intensity_pub_
 
ros::Publisher io_pub_
 
ros::Publisher pointcloud_pub_
 
ros::NodeHandle priv_nh_
 
ros::Publisher roi_pub_
 
image_transport::Publisher state_pub_
 

Detailed Description

A compound publisher for the driver's topics.

This class encapsulates all necessary publishers to keep the driver's thread management nice and clear.

Definition at line 61 of file compound_publisher.h.

Constructor & Destructor Documentation

◆ CompoundPublisher()

CompoundPublisher::CompoundPublisher ( )

Definition at line 34 of file compound_publisher.cpp.

◆ ~CompoundPublisher()

virtual CompoundPublisher::~CompoundPublisher ( )
inlinevirtual

Definition at line 65 of file compound_publisher.h.

Member Function Documentation

◆ publish()

void CompoundPublisher::publish ( const std_msgs::Header header,
visionary::SafeVisionaryData &  frame_data 
)

Publish once with all registered publishers.

Parameters
headerHeader for this data
frame_dataThe sensor's data to publish

Definition at line 53 of file compound_publisher.cpp.

◆ publishCameraInfo()

void CompoundPublisher::publishCameraInfo ( const std_msgs::Header header,
const visionary::SafeVisionaryData &  frame_data 
)
private

Publishes the camera information of the sensor.

Parameters
headerHeader for this data
frame_dataThe sensor's data to publish

Definition at line 98 of file compound_publisher.cpp.

◆ publishDepthImage()

void CompoundPublisher::publishDepthImage ( const std_msgs::Header header,
const visionary::SafeVisionaryData &  frame_data 
)
private

Publishes the raw depth image.

Parameters
headerHeader for this data
frame_dataThe sensor's data to publish

Definition at line 200 of file compound_publisher.cpp.

◆ publishDeviceStatus()

void CompoundPublisher::publishDeviceStatus ( const std_msgs::Header header,
const visionary::SafeVisionaryData &  frame_data 
)
private

Publishes the device status.

Parameters
headerHeader for this data
frame_dataThe sensor's data to publish

Definition at line 237 of file compound_publisher.cpp.

◆ publishFieldInformation()

void CompoundPublisher::publishFieldInformation ( const std_msgs::Header header,
const visionary::SafeVisionaryData &  frame_data 
)
private

Publishes the evaluation of the configured safety fields.

Parameters
headerHeader for this data
frame_dataThe sensor's data to publish

Definition at line 363 of file compound_publisher.cpp.

◆ publishIMUData()

void CompoundPublisher::publishIMUData ( const std_msgs::Header header,
const visionary::SafeVisionaryData &  frame_data 
)
private

Publishes the values of the IMU.

Parameters
headerHeader for this data
frame_dataThe sensor's data to publish

Definition at line 182 of file compound_publisher.cpp.

◆ publishIntensityImage()

void CompoundPublisher::publishIntensityImage ( const std_msgs::Header header,
const visionary::SafeVisionaryData &  frame_data 
)
private

Publishes the raw intensity image.

Parameters
headerHeader for this data
frame_dataThe sensor's data to publish

Definition at line 206 of file compound_publisher.cpp.

◆ publishIOs()

void CompoundPublisher::publishIOs ( const std_msgs::Header header,
const visionary::SafeVisionaryData &  frame_data 
)
private

Publishes the state of the IO ports.

Parameters
headerHeader for this data
frame_dataThe sensor's data to publish

Definition at line 276 of file compound_publisher.cpp.

◆ publishPointCloud()

void CompoundPublisher::publishPointCloud ( const std_msgs::Header header,
visionary::SafeVisionaryData &  frame_data 
)
private

Publishes the generated 3D Pointcloud.

Parameters
headerHeader for this data
frame_dataThe sensor's data to publish

Definition at line 122 of file compound_publisher.cpp.

◆ publishROI()

void CompoundPublisher::publishROI ( const std_msgs::Header header,
const visionary::SafeVisionaryData &  frame_data 
)
private

Publishes the regions of interest.

Parameters
headerHeader for this data
frame_dataThe sensor's data to publish

Definition at line 326 of file compound_publisher.cpp.

◆ publishStateMap()

void CompoundPublisher::publishStateMap ( const std_msgs::Header header,
const visionary::SafeVisionaryData &  frame_data 
)
private

Publishes the raw state map of each pixel.

Parameters
headerHeader for this data
frame_dataThe sensor's data to publish

Definition at line 212 of file compound_publisher.cpp.

◆ Vec16ToImage()

sensor_msgs::ImagePtr CompoundPublisher::Vec16ToImage ( const std_msgs::Header header,
const visionary::SafeVisionaryData &  frame_data,
std::vector< uint16_t >  vec 
)
private

Creates an image from a data vector.

Parameters
headerHeader for this data
frame_dataThe sensor's data to publish
vecThe converted data vector
Returns
Image projection of input data vector

Definition at line 219 of file compound_publisher.cpp.

◆ Vec8ToImage()

sensor_msgs::ImagePtr CompoundPublisher::Vec8ToImage ( const std_msgs::Header header,
const visionary::SafeVisionaryData &  frame_data,
std::vector< uint8_t >  vec 
)
private

Creates an image from a data vector.

Parameters
headerHeader for this data
frame_dataThe sensor's data to publish
vecThe converted data vector
Returns
Image projection of input data vector

Definition at line 227 of file compound_publisher.cpp.

Member Data Documentation

◆ camera_info_pub_

ros::Publisher CompoundPublisher::camera_info_pub_
private

Definition at line 178 of file compound_publisher.h.

◆ depth_pub_

image_transport::Publisher CompoundPublisher::depth_pub_
private

Definition at line 186 of file compound_publisher.h.

◆ device_status_pub_

ros::Publisher CompoundPublisher::device_status_pub_
private

Definition at line 181 of file compound_publisher.h.

◆ field_pub_

ros::Publisher CompoundPublisher::field_pub_
private

Definition at line 184 of file compound_publisher.h.

◆ imu_pub_

ros::Publisher CompoundPublisher::imu_pub_
private

Definition at line 180 of file compound_publisher.h.

◆ intensity_pub_

image_transport::Publisher CompoundPublisher::intensity_pub_
private

Definition at line 187 of file compound_publisher.h.

◆ io_pub_

ros::Publisher CompoundPublisher::io_pub_
private

Definition at line 182 of file compound_publisher.h.

◆ pointcloud_pub_

ros::Publisher CompoundPublisher::pointcloud_pub_
private

Definition at line 179 of file compound_publisher.h.

◆ priv_nh_

ros::NodeHandle CompoundPublisher::priv_nh_
private

Definition at line 189 of file compound_publisher.h.

◆ roi_pub_

ros::Publisher CompoundPublisher::roi_pub_
private

Definition at line 183 of file compound_publisher.h.

◆ state_pub_

image_transport::Publisher CompoundPublisher::state_pub_
private

Definition at line 188 of file compound_publisher.h.


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


sick_safevisionary_driver
Author(s):
autogenerated on Fri Oct 20 2023 02:09:16