color_laser.h
Go to the documentation of this file.
1 
34 #ifndef MULTISENSE_ROS_COLOR_LASER_H
35 #define MULTISENSE_ROS_COLOR_LASER_H
36 
37 #include <mutex>
38 #include <string>
39 #include <vector>
40 
41 #include <ros/ros.h>
42 #include <sensor_msgs/PointCloud2.h>
43 #include <sensor_msgs/Image.h>
44 #include <sensor_msgs/CameraInfo.h>
45 
46 namespace multisense_ros{
47 
49 {
50  public:
51 
52  ColorLaser(
53  ros::NodeHandle& nh,
54  const std::string &tf_prefix
55  );
56 
57  ~ColorLaser() = default;
58 
59  //
60  // Callbacks for subscriptions to ROS topics
61 
62  void colorImageCallback(const sensor_msgs::Image::ConstPtr& message);
63  void laserPointCloudCallback(sensor_msgs::PointCloud2::Ptr message);
64  void cameraInfoCallback(const sensor_msgs::CameraInfo::ConstPtr& message);
65 
66  private:
67 
68  //
69  // Callback used to setup subscribers once there is a subscription
70  // to the lidar_points2_color topic
71 
72  void startStreaming();
73  void stopStreaming();
74 
75  //
76  // Messages for local storage of sensor data
77 
78  sensor_msgs::Image color_image_;
79  sensor_msgs::CameraInfo camera_info_;
80 
81  sensor_msgs::PointCloud2 color_laser_pointcloud_;
82 
83  //
84  // Publisher for the colorized laser point cloud
85 
87 
88  //
89  // Subscribers for image, point cloud, and camera info topics
90 
94 
95  //
96  // Node handle used for publishing/subscribing to topics
97 
99 
100  //
101  // Mutex to assure callbacks don't interfere with one another
102 
103  std::mutex data_lock_;
104 
105  //
106  // The number of channels in our color image
107 
109 
110  //
111  // The TF prefix to publish laser point clouds with
112 
113  std::string tf_prefix_;
114 };
115 
116 }// namespace
117 
118 #endif
119 
ros::Subscriber color_image_sub_
Definition: color_laser.h:91
ros::Publisher color_laser_publisher_
Definition: color_laser.h:86
sensor_msgs::Image color_image_
Definition: color_laser.h:78
sensor_msgs::CameraInfo camera_info_
Definition: color_laser.h:79
void laserPointCloudCallback(sensor_msgs::PointCloud2::Ptr message)
Definition: color_laser.cpp:94
ros::Subscriber laser_pointcloud_sub_
Definition: color_laser.h:92
void cameraInfoCallback(const sensor_msgs::CameraInfo::ConstPtr &message)
Definition: color_laser.cpp:85
ros::NodeHandle node_handle_
Definition: color_laser.h:98
void colorImageCallback(const sensor_msgs::Image::ConstPtr &message)
Definition: color_laser.cpp:66
ColorLaser(ros::NodeHandle &nh, const std::string &tf_prefix)
Definition: color_laser.cpp:49
ros::Subscriber camera_info_sub_
Definition: color_laser.h:93
sensor_msgs::PointCloud2 color_laser_pointcloud_
Definition: color_laser.h:81


multisense_ros
Author(s):
autogenerated on Sun Mar 14 2021 02:34:55