camera.h
Go to the documentation of this file.
1 
34 #ifndef MULTISENSE_ROS_CAMERA_H
35 #define MULTISENSE_ROS_CAMERA_H
36 
37 #include <memory>
38 #include <mutex>
39 #include <thread>
40 
41 #include <ros/ros.h>
42 
47 #include <stereo_msgs/DisparityImage.h>
48 #include <sensor_msgs/PointCloud2.h>
50 
51 
52 #include <multisense_lib/MultiSenseChannel.hh>
53 #include <multisense_ros/RawCamData.h>
55 
56 namespace multisense_ros {
57 
58 class Camera {
59 public:
61  const std::string& tf_prefix);
62  ~Camera();
63 
64  void updateConfig(const crl::multisense::image::Config& config);
65 
66  void monoCallback(const crl::multisense::image::Header& header);
67  void rectCallback(const crl::multisense::image::Header& header);
76 
77  void borderClipChanged(const BorderClip &borderClipType, double borderClipValue);
78 
79  void maxPointCloudRangeChanged(double range);
80 
81 private:
82  //
83  // Node names
84 
85  static constexpr char LEFT[] = "left";
86  static constexpr char RIGHT[] = "right";
87  static constexpr char AUX[] = "aux";
88  static constexpr char CALIBRATION[] = "calibration";
89 
90  //
91  // Frames
92 
93  static constexpr char LEFT_CAMERA_FRAME[] = "/left_camera_frame";
94  static constexpr char LEFT_RECTIFIED_FRAME[] = "/left_camera_optical_frame";
95  static constexpr char RIGHT_CAMERA_FRAME[] = "/right_camera_frame";
96  static constexpr char RIGHT_RECTIFIED_FRAME[] = "/right_camera_optical_frame";
97  static constexpr char AUX_CAMERA_FRAME[] = "/aux_camera_frame";
98  static constexpr char AUX_RECTIFIED_FRAME[] = "/aux_camera_optical_frame";
99 
100  //
101  // Topic names
102 
103  static constexpr char DEVICE_INFO_TOPIC[] = "device_info";
104  static constexpr char RAW_CAM_CAL_TOPIC[] = "raw_cam_cal";
105  static constexpr char RAW_CAM_CONFIG_TOPIC[] = "raw_cam_config";
106  static constexpr char RAW_CAM_DATA_TOPIC[] = "raw_cam_data";
107  static constexpr char HISTOGRAM_TOPIC[] = "histogram";
108  static constexpr char MONO_TOPIC[] = "image_mono";
109  static constexpr char RECT_TOPIC[] = "image_rect";
110  static constexpr char DISPARITY_TOPIC[] = "disparity";
111  static constexpr char DISPARITY_IMAGE_TOPIC[] = "disparity_image";
112  static constexpr char DEPTH_TOPIC[] = "depth";
113  static constexpr char OPENNI_DEPTH_TOPIC[] = "openni_depth";
114  static constexpr char COST_TOPIC[] = "cost";
115  static constexpr char COLOR_TOPIC[] = "image_color";
116  static constexpr char RECT_COLOR_TOPIC[] = "image_rect_color";
117  static constexpr char POINTCLOUD_TOPIC[] = "image_points2";
118  static constexpr char COLOR_POINTCLOUD_TOPIC[] = "image_points2_color";
119  static constexpr char ORGANIZED_POINTCLOUD_TOPIC[] = "organized_image_points2";
120  static constexpr char COLOR_ORGANIZED_POINTCLOUD_TOPIC[] = "organized_image_points2_color";
121  static constexpr char MONO_CAMERA_INFO_TOPIC[] = "image_mono/camera_info";
122  static constexpr char RECT_CAMERA_INFO_TOPIC[] = "image_rect/camera_info";
123  static constexpr char COLOR_CAMERA_INFO_TOPIC[] = "image_color/camera_info";
124  static constexpr char RECT_COLOR_CAMERA_INFO_TOPIC[] = "image_rect_color/camera_info";
125  static constexpr char DEPTH_CAMERA_INFO_TOPIC[] = "depth/camera_info";
126  static constexpr char DISPARITY_CAMERA_INFO_TOPIC[] = "disparity/camera_info";
127  static constexpr char COST_CAMERA_INFO_TOPIC[] = "cost/camera_info";
128 
129  //
130  // Device stream control
131 
134  void stop();
135 
136  //
137  // Republish camera info messages by publishing the current messages
138  // Used whenever the resolution of the camera changes
139 
140  void publishAllCameraInfo();
141 
142  //
143  // CRL sensor API
144 
146 
147  //
148  // Driver nodes
149 
155 
156  //
157  // Image transports
158 
174 
175  //
176  // Data publishers
177 
183  image_transport::Publisher ni_depth_cam_pub_; // publish depth infomation in the openNI format
190 
205 
208 
211 
215 
218 
219  //
220  // Raw data publishers
221 
227 
228  //
229  // Store outgoing messages for efficiency
230 
231  sensor_msgs::Image left_mono_image_;
232  sensor_msgs::Image right_mono_image_;
233  sensor_msgs::Image left_rect_image_;
234  sensor_msgs::Image right_rect_image_;
235  sensor_msgs::Image depth_image_;
236  sensor_msgs::Image ni_depth_image_;
237  sensor_msgs::PointCloud2 luma_point_cloud_;
238  sensor_msgs::PointCloud2 color_point_cloud_;
239  sensor_msgs::PointCloud2 luma_organized_point_cloud_;
240  sensor_msgs::PointCloud2 color_organized_point_cloud_;
241 
242  sensor_msgs::Image aux_mono_image_;
243  sensor_msgs::Image left_rgb_image_;
244  sensor_msgs::Image aux_rgb_image_;
245  sensor_msgs::Image left_rgb_rect_image_;
246  sensor_msgs::Image aux_rect_image_;
247  sensor_msgs::Image aux_rgb_rect_image_;
248 
249  sensor_msgs::Image left_disparity_image_;
250  sensor_msgs::Image left_disparity_cost_image_;
251  sensor_msgs::Image right_disparity_image_;
252 
253  stereo_msgs::DisparityImage left_stereo_disparity_;
254  stereo_msgs::DisparityImage right_stereo_disparity_;
255 
256  multisense_ros::RawCamData raw_cam_data_;
257 
258  std::vector<uint8_t> pointcloud_color_buffer_;
259  std::vector<uint8_t> pointcloud_rect_color_buffer_;
260 
261  //
262  // Calibration from sensor
263 
266  std::vector<crl::multisense::system::DeviceMode> device_modes_;
267 
268  //
269  // Calibration manager
270 
271  std::shared_ptr<StereoCalibrationManger> stereo_calibration_manager_;
272 
273  //
274  // The frame IDs
275 
276  const std::string frame_id_left_;
277  const std::string frame_id_right_;
278  const std::string frame_id_aux_;
279  const std::string frame_id_rectified_left_;
280  const std::string frame_id_rectified_right_;
281  const std::string frame_id_rectified_aux_;
282 
284 
285  //
286  // Stream subscriptions
287 
288  typedef std::map<crl::multisense::DataSource, int32_t> StreamMapType;
289  std::mutex stream_lock_;
290  StreamMapType stream_map_;
291 
292  //
293  // Max distance from the camera for a point to be considered valid
294 
295  double pointcloud_max_range_ = 15.0;
296 
297  //
298  // Histogram tracking
299 
300  int64_t last_frame_id_ = -1;
301 
302  //
303  // The mask used to perform the border clipping of the disparity image
304 
306  double border_clip_value_ = 0.0;
307 
308  //
309  // Storage of images which we use for pointcloud colorizing
310 
311  std::unordered_map<crl::multisense::DataSource, std::shared_ptr<BufferWrapper<crl::multisense::image::Header>>> image_buffers_;
312 
313  //
314  // Has a 3rd aux color camera
315 
316  bool has_aux_camera_ = false;
317 };
318 
319 }
320 
321 #endif
ros::Publisher left_rgb_cam_info_pub_
Definition: camera.h:198
static constexpr char AUX_RECTIFIED_FRAME[]
Definition: camera.h:98
const std::string frame_id_rectified_right_
Definition: camera.h:280
static constexpr char LEFT[]
Definition: camera.h:85
std::vector< crl::multisense::system::DeviceMode > device_modes_
Definition: camera.h:266
image_transport::Publisher right_disparity_pub_
Definition: camera.h:213
static constexpr char RECT_CAMERA_INFO_TOPIC[]
Definition: camera.h:122
void maxPointCloudRangeChanged(double range)
Definition: camera.cpp:725
ros::Publisher luma_organized_point_cloud_pub_
Definition: camera.h:209
void pointCloudCallback(const crl::multisense::image::Header &header)
Definition: camera.cpp:1369
void rawCamDataCallback(const crl::multisense::image::Header &header)
Definition: camera.cpp:1636
image_transport::ImageTransport disparity_cost_transport_
Definition: camera.h:169
image_transport::Publisher left_mono_cam_pub_
Definition: camera.h:178
static constexpr char RAW_CAM_DATA_TOPIC[]
Definition: camera.h:106
sensor_msgs::Image right_rect_image_
Definition: camera.h:234
static constexpr char COLOR_CAMERA_INFO_TOPIC[]
Definition: camera.h:123
static constexpr char RIGHT_CAMERA_FRAME[]
Definition: camera.h:95
void disparityImageCallback(const crl::multisense::image::Header &header)
Definition: camera.cpp:826
ros::NodeHandle device_nh_
Definition: camera.h:150
tf2_ros::StaticTransformBroadcaster static_tf_broadcaster_
Definition: camera.h:283
static constexpr char DEPTH_TOPIC[]
Definition: camera.h:112
ros::Publisher right_stereo_disparity_pub_
Definition: camera.h:217
static constexpr char MONO_TOPIC[]
Definition: camera.h:108
ros::Publisher right_rect_cam_info_pub_
Definition: camera.h:194
void colorImageCallback(const crl::multisense::image::Header &header)
Definition: camera.cpp:1677
static constexpr char DISPARITY_CAMERA_INFO_TOPIC[]
Definition: camera.h:126
static constexpr char RIGHT[]
Definition: camera.h:86
static constexpr char COST_CAMERA_INFO_TOPIC[]
Definition: camera.h:127
image_transport::ImageTransport left_rect_transport_
Definition: camera.h:161
sensor_msgs::Image ni_depth_image_
Definition: camera.h:236
sensor_msgs::PointCloud2 luma_organized_point_cloud_
Definition: camera.h:239
sensor_msgs::PointCloud2 luma_point_cloud_
Definition: camera.h:237
void monoCallback(const crl::multisense::image::Header &header)
Definition: camera.cpp:1001
image_transport::Publisher left_disparity_cost_pub_
Definition: camera.h:214
sensor_msgs::PointCloud2 color_point_cloud_
Definition: camera.h:238
ros::Publisher left_stereo_disparity_pub_
Definition: camera.h:216
ros::Publisher luma_point_cloud_pub_
Definition: camera.h:206
ros::NodeHandle aux_nh_
Definition: camera.h:153
ros::Publisher depth_cam_info_pub_
Definition: camera.h:200
ros::Publisher histogram_pub_
Definition: camera.h:226
ros::Publisher left_mono_cam_info_pub_
Definition: camera.h:191
Camera(crl::multisense::Channel *driver, const std::string &tf_prefix)
Definition: camera.cpp:258
const std::string frame_id_left_
Definition: camera.h:276
static constexpr char ORGANIZED_POINTCLOUD_TOPIC[]
Definition: camera.h:119
sensor_msgs::Image right_disparity_image_
Definition: camera.h:251
std::unordered_map< crl::multisense::DataSource, std::shared_ptr< BufferWrapper< crl::multisense::image::Header > > > image_buffers_
Definition: camera.h:311
static constexpr char DEVICE_INFO_TOPIC[]
Definition: camera.h:103
static constexpr char RECT_TOPIC[]
Definition: camera.h:109
double border_clip_value_
Definition: camera.h:306
sensor_msgs::Image depth_image_
Definition: camera.h:235
image_transport::ImageTransport aux_rgb_transport_
Definition: camera.h:171
void disconnectStream(crl::multisense::DataSource disableMask)
Definition: camera.cpp:2004
image_transport::Publisher aux_mono_cam_pub_
Definition: camera.h:187
static constexpr char DISPARITY_IMAGE_TOPIC[]
Definition: camera.h:111
void depthCallback(const crl::multisense::image::Header &header)
Definition: camera.cpp:1235
void connectStream(crl::multisense::DataSource enableMask)
Definition: camera.cpp:1985
ros::Publisher raw_cam_config_pub_
Definition: camera.h:223
static constexpr char COST_TOPIC[]
Definition: camera.h:114
sensor_msgs::Image left_disparity_cost_image_
Definition: camera.h:250
image_transport::ImageTransport right_mono_transport_
Definition: camera.h:160
image_transport::ImageTransport left_rgb_transport_
Definition: camera.h:163
void colorizeCallback(const crl::multisense::image::Header &header)
Definition: camera.cpp:1861
ros::Publisher right_mono_cam_info_pub_
Definition: camera.h:192
const std::string frame_id_right_
Definition: camera.h:277
stereo_msgs::DisparityImage left_stereo_disparity_
Definition: camera.h:253
image_transport::ImageTransport aux_mono_transport_
Definition: camera.h:170
ros::Publisher aux_rgb_cam_info_pub_
Definition: camera.h:202
image_transport::Publisher right_mono_cam_pub_
Definition: camera.h:179
void borderClipChanged(const BorderClip &borderClipType, double borderClipValue)
Definition: camera.cpp:716
StreamMapType stream_map_
Definition: camera.h:290
crl::multisense::system::DeviceInfo device_info_
Definition: camera.h:265
image_transport::CameraPublisher aux_rgb_rect_cam_pub_
Definition: camera.h:189
ros::Publisher aux_rect_cam_info_pub_
Definition: camera.h:203
sensor_msgs::Image left_mono_image_
Definition: camera.h:231
image_transport::Publisher ni_depth_cam_pub_
Definition: camera.h:183
void rectCallback(const crl::multisense::image::Header &header)
Definition: camera.cpp:1109
image_transport::ImageTransport aux_rgb_rect_transport_
Definition: camera.h:173
const std::string frame_id_rectified_left_
Definition: camera.h:279
void updateConfig(const crl::multisense::image::Config &config)
Definition: camera.cpp:1877
image_transport::Publisher left_disparity_pub_
Definition: camera.h:212
ros::Publisher raw_cam_data_pub_
Definition: camera.h:222
image_transport::CameraPublisher left_rgb_rect_cam_pub_
Definition: camera.h:185
ros::Publisher left_disp_cam_info_pub_
Definition: camera.h:195
image_transport::Publisher depth_cam_pub_
Definition: camera.h:182
BorderClip border_clip_type_
Definition: camera.h:305
std::map< crl::multisense::DataSource, int32_t > StreamMapType
Definition: camera.h:288
image_transport::ImageTransport aux_rect_transport_
Definition: camera.h:172
ros::NodeHandle right_nh_
Definition: camera.h:152
image_transport::CameraPublisher right_rect_cam_pub_
Definition: camera.h:181
static constexpr char LEFT_CAMERA_FRAME[]
Definition: camera.h:93
image_transport::ImageTransport left_mono_transport_
Definition: camera.h:159
image_transport::CameraPublisher aux_rect_cam_pub_
Definition: camera.h:188
ros::Publisher raw_cam_cal_pub_
Definition: camera.h:224
static constexpr char LEFT_RECTIFIED_FRAME[]
Definition: camera.h:94
image_transport::CameraPublisher left_rect_cam_pub_
Definition: camera.h:180
sensor_msgs::Image left_rect_image_
Definition: camera.h:233
ros::Publisher right_disp_cam_info_pub_
Definition: camera.h:196
crl::multisense::Channel * driver_
Definition: camera.h:145
std::shared_ptr< StereoCalibrationManger > stereo_calibration_manager_
Definition: camera.h:271
ros::Publisher device_info_pub_
Definition: camera.h:225
static constexpr char RAW_CAM_CAL_TOPIC[]
Definition: camera.h:104
image_transport::Publisher left_rgb_cam_pub_
Definition: camera.h:184
const std::string frame_id_rectified_aux_
Definition: camera.h:281
static constexpr char RECT_COLOR_CAMERA_INFO_TOPIC[]
Definition: camera.h:124
static constexpr char COLOR_POINTCLOUD_TOPIC[]
Definition: camera.h:118
static constexpr char OPENNI_DEPTH_TOPIC[]
Definition: camera.h:113
static constexpr char COLOR_TOPIC[]
Definition: camera.h:115
image_transport::ImageTransport left_rgb_rect_transport_
Definition: camera.h:164
std::mutex stream_lock_
Definition: camera.h:289
ros::NodeHandle calibration_nh_
Definition: camera.h:154
ros::Publisher aux_rgb_rect_cam_info_pub_
Definition: camera.h:204
sensor_msgs::Image aux_rgb_image_
Definition: camera.h:244
sensor_msgs::Image left_rgb_image_
Definition: camera.h:243
sensor_msgs::Image right_mono_image_
Definition: camera.h:232
static constexpr char AUX_CAMERA_FRAME[]
Definition: camera.h:97
image_transport::ImageTransport depth_transport_
Definition: camera.h:165
ros::Publisher left_rgb_rect_cam_info_pub_
Definition: camera.h:199
void histogramCallback(const crl::multisense::image::Header &header)
Definition: camera.cpp:730
stereo_msgs::DisparityImage right_stereo_disparity_
Definition: camera.h:254
static constexpr char RECT_COLOR_TOPIC[]
Definition: camera.h:116
uint32_t DataSource
ros::NodeHandle left_nh_
Definition: camera.h:151
double pointcloud_max_range_
Definition: camera.h:295
image_transport::ImageTransport right_rect_transport_
Definition: camera.h:162
ros::Publisher left_cost_cam_info_pub_
Definition: camera.h:197
static constexpr char DEPTH_CAMERA_INFO_TOPIC[]
Definition: camera.h:125
static constexpr char HISTOGRAM_TOPIC[]
Definition: camera.h:107
image_transport::Publisher aux_rgb_cam_pub_
Definition: camera.h:186
image_transport::ImageTransport ni_depth_transport_
Definition: camera.h:166
image_transport::ImageTransport disparity_right_transport_
Definition: camera.h:168
static constexpr char POINTCLOUD_TOPIC[]
Definition: camera.h:117
sensor_msgs::Image aux_mono_image_
Definition: camera.h:242
ros::Publisher left_rect_cam_info_pub_
Definition: camera.h:193
std::vector< uint8_t > pointcloud_rect_color_buffer_
Definition: camera.h:259
void jpegImageCallback(const crl::multisense::image::Header &header)
Definition: camera.cpp:766
sensor_msgs::Image left_disparity_image_
Definition: camera.h:249
ros::Publisher color_organized_point_cloud_pub_
Definition: camera.h:210
sensor_msgs::Image aux_rgb_rect_image_
Definition: camera.h:247
static constexpr char MONO_CAMERA_INFO_TOPIC[]
Definition: camera.h:121
static constexpr char CALIBRATION[]
Definition: camera.h:88
image_transport::ImageTransport disparity_left_transport_
Definition: camera.h:167
static constexpr char RIGHT_RECTIFIED_FRAME[]
Definition: camera.h:96
sensor_msgs::PointCloud2 color_organized_point_cloud_
Definition: camera.h:240
crl::multisense::system::VersionInfo version_info_
Definition: camera.h:264
static constexpr char AUX[]
Definition: camera.h:87
static constexpr char COLOR_ORGANIZED_POINTCLOUD_TOPIC[]
Definition: camera.h:120
sensor_msgs::Image left_rgb_rect_image_
Definition: camera.h:245
const std::string frame_id_aux_
Definition: camera.h:278
ros::Publisher aux_mono_cam_info_pub_
Definition: camera.h:201
multisense_ros::RawCamData raw_cam_data_
Definition: camera.h:256
ros::Publisher color_point_cloud_pub_
Definition: camera.h:207
int64_t last_frame_id_
Definition: camera.h:300
sensor_msgs::Image aux_rect_image_
Definition: camera.h:246
std::vector< uint8_t > pointcloud_color_buffer_
Definition: camera.h:258
static constexpr char DISPARITY_TOPIC[]
Definition: camera.h:110
static constexpr char RAW_CAM_CONFIG_TOPIC[]
Definition: camera.h:105


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