Go to the documentation of this file.
31 #ifndef SICK_SAFEVISIONARY_DRIVER_COMPOUND_PUBLISHER_H_INCLUDED
32 #define SICK_SAFEVISIONARY_DRIVER_COMPOUND_PUBLISHER_H_INCLUDED
39 #include <sensor_msgs/CameraInfo.h>
40 #include <sensor_msgs/Imu.h>
41 #include <sensor_msgs/PointCloud2.h>
42 #include <std_msgs/Header.h>
45 #include <opencv2/opencv.hpp>
48 #include <sick_safevisionary_base/PointXYZ.h>
49 #include <sick_safevisionary_base/SafeVisionaryData.h>
50 #include <sick_safevisionary_msgs/CameraIO.h>
51 #include <sick_safevisionary_msgs/DeviceStatus.h>
52 #include <sick_safevisionary_msgs/FieldInformationArray.h>
53 #include <sick_safevisionary_msgs/ROIArray.h>
72 void publish(
const std_msgs::Header& header, visionary::SafeVisionaryData& frame_data);
82 const visionary::SafeVisionaryData& frame_data);
89 void publishPointCloud(
const std_msgs::Header& header, visionary::SafeVisionaryData& frame_data);
97 const visionary::SafeVisionaryData& frame_data);
105 const visionary::SafeVisionaryData& frame_data);
112 void publishIOs(
const std_msgs::Header& header,
const visionary::SafeVisionaryData& frame_data);
119 void publishROI(
const std_msgs::Header& header,
const visionary::SafeVisionaryData& frame_data);
127 const visionary::SafeVisionaryData& frame_data);
135 const visionary::SafeVisionaryData& frame_data);
143 const visionary::SafeVisionaryData& frame_data);
151 const visionary::SafeVisionaryData& frame_data);
162 sensor_msgs::ImagePtr
Vec16ToImage(
const std_msgs::Header& header,
163 const visionary::SafeVisionaryData& frame_data,
164 std::vector<uint16_t> vec);
174 sensor_msgs::ImagePtr
Vec8ToImage(
const std_msgs::Header& header,
175 const visionary::SafeVisionaryData& frame_data,
176 std::vector<uint8_t> vec);
ros::Publisher camera_info_pub_
void publishFieldInformation(const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
Publishes the evaluation of the configured safety fields.
image_transport::Publisher intensity_pub_
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.
void publishCameraInfo(const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
Publishes the camera information of the sensor.
ros::Publisher device_status_pub_
A compound publisher for the driver's topics.
image_transport::Publisher state_pub_
void publishIOs(const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
Publishes the state of the IO ports.
void publishROI(const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
Publishes the regions of interest.
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.
void publishIntensityImage(const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
Publishes the raw intensity image.
void publishIMUData(const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
Publishes the values of the IMU.
void publishStateMap(const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
Publishes the raw state map of each pixel.
image_transport::Publisher depth_pub_
void publishDepthImage(const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
Publishes the raw depth image.
void publishPointCloud(const std_msgs::Header &header, visionary::SafeVisionaryData &frame_data)
Publishes the generated 3D Pointcloud.
virtual ~CompoundPublisher()
ros::Publisher pointcloud_pub_
ros::Publisher field_pub_
void publishDeviceStatus(const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
Publishes the device status.
void publish(const std_msgs::Header &header, visionary::SafeVisionaryData &frame_data)
Publish once with all registered publishers.