compound_publisher.h
Go to the documentation of this file.
1 // -- BEGIN LICENSE BLOCK ----------------------------------------------
20 // -- END LICENSE BLOCK ------------------------------------------------
21 
22 //----------------------------------------------------------------------
29 //----------------------------------------------------------------------
30 
31 #ifndef SICK_SAFEVISIONARY_DRIVER_COMPOUND_PUBLISHER_H_INCLUDED
32 #define SICK_SAFEVISIONARY_DRIVER_COMPOUND_PUBLISHER_H_INCLUDED
33 
34 
36 
38 #include <ros/message_traits.h>
39 #include <sensor_msgs/CameraInfo.h>
40 #include <sensor_msgs/Imu.h>
41 #include <sensor_msgs/PointCloud2.h>
42 #include <std_msgs/Header.h>
43 
44 #include <cv_bridge/cv_bridge.h>
45 #include <opencv2/opencv.hpp>
46 
47 
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>
54 
62 {
63 public:
65  virtual ~CompoundPublisher(){};
72  void publish(const std_msgs::Header& header, visionary::SafeVisionaryData& frame_data);
73 
74 private:
81  void publishCameraInfo(const std_msgs::Header& header,
82  const visionary::SafeVisionaryData& frame_data);
89  void publishPointCloud(const std_msgs::Header& header, visionary::SafeVisionaryData& frame_data);
96  void publishIMUData(const std_msgs::Header& header,
97  const visionary::SafeVisionaryData& frame_data);
104  void publishDeviceStatus(const std_msgs::Header& header,
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);
126  void publishFieldInformation(const std_msgs::Header& header,
127  const visionary::SafeVisionaryData& frame_data);
134  void publishDepthImage(const std_msgs::Header& header,
135  const visionary::SafeVisionaryData& frame_data);
142  void publishIntensityImage(const std_msgs::Header& header,
143  const visionary::SafeVisionaryData& frame_data);
150  void publishStateMap(const std_msgs::Header& header,
151  const visionary::SafeVisionaryData& frame_data);
152 
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);
177 
185 
190 };
191 
192 #endif /* SICK_SAFEVISIONARY_DRIVER_COMPOUND_PUBLISHER_H_INCLUDED */
CompoundPublisher::camera_info_pub_
ros::Publisher camera_info_pub_
Definition: compound_publisher.h:178
CompoundPublisher::publishFieldInformation
void publishFieldInformation(const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
Publishes the evaluation of the configured safety fields.
Definition: compound_publisher.cpp:363
CompoundPublisher::intensity_pub_
image_transport::Publisher intensity_pub_
Definition: compound_publisher.h:187
CompoundPublisher::Vec8ToImage
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.
Definition: compound_publisher.cpp:227
ros::Publisher
CompoundPublisher::roi_pub_
ros::Publisher roi_pub_
Definition: compound_publisher.h:183
CompoundPublisher::publishCameraInfo
void publishCameraInfo(const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
Publishes the camera information of the sensor.
Definition: compound_publisher.cpp:98
CompoundPublisher::device_status_pub_
ros::Publisher device_status_pub_
Definition: compound_publisher.h:181
CompoundPublisher
A compound publisher for the driver's topics.
Definition: compound_publisher.h:61
CompoundPublisher::state_pub_
image_transport::Publisher state_pub_
Definition: compound_publisher.h:188
CompoundPublisher::publishIOs
void publishIOs(const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
Publishes the state of the IO ports.
Definition: compound_publisher.cpp:276
CompoundPublisher::publishROI
void publishROI(const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
Publishes the regions of interest.
Definition: compound_publisher.cpp:326
publisher.h
CompoundPublisher::Vec16ToImage
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.
Definition: compound_publisher.cpp:219
CompoundPublisher::imu_pub_
ros::Publisher imu_pub_
Definition: compound_publisher.h:180
CompoundPublisher::publishIntensityImage
void publishIntensityImage(const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
Publishes the raw intensity image.
Definition: compound_publisher.cpp:206
CompoundPublisher::CompoundPublisher
CompoundPublisher()
Definition: compound_publisher.cpp:34
message_traits.h
CompoundPublisher::publishIMUData
void publishIMUData(const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
Publishes the values of the IMU.
Definition: compound_publisher.cpp:182
image_transport.h
CompoundPublisher::publishStateMap
void publishStateMap(const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
Publishes the raw state map of each pixel.
Definition: compound_publisher.cpp:212
CompoundPublisher::priv_nh_
ros::NodeHandle priv_nh_
Definition: compound_publisher.h:189
image_transport::Publisher
CompoundPublisher::io_pub_
ros::Publisher io_pub_
Definition: compound_publisher.h:182
CompoundPublisher::depth_pub_
image_transport::Publisher depth_pub_
Definition: compound_publisher.h:186
cv_bridge.h
CompoundPublisher::publishDepthImage
void publishDepthImage(const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
Publishes the raw depth image.
Definition: compound_publisher.cpp:200
CompoundPublisher::publishPointCloud
void publishPointCloud(const std_msgs::Header &header, visionary::SafeVisionaryData &frame_data)
Publishes the generated 3D Pointcloud.
Definition: compound_publisher.cpp:122
CompoundPublisher::~CompoundPublisher
virtual ~CompoundPublisher()
Definition: compound_publisher.h:65
CompoundPublisher::pointcloud_pub_
ros::Publisher pointcloud_pub_
Definition: compound_publisher.h:179
CompoundPublisher::field_pub_
ros::Publisher field_pub_
Definition: compound_publisher.h:184
CompoundPublisher::publishDeviceStatus
void publishDeviceStatus(const std_msgs::Header &header, const visionary::SafeVisionaryData &frame_data)
Publishes the device status.
Definition: compound_publisher.cpp:237
CompoundPublisher::publish
void publish(const std_msgs::Header &header, visionary::SafeVisionaryData &frame_data)
Publish once with all registered publishers.
Definition: compound_publisher.cpp:53
ros::NodeHandle


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