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


multisense_ros
Author(s):
autogenerated on Sat Apr 6 2019 02:16:53