camera_core.cpp
Go to the documentation of this file.
1 /******************************************************************************
2  Copyright (c) 2016, Intel Corporation
3  All rights reserved.
4 
5  Redistribution and use in source and binary forms, with or without
6  modification, are permitted provided that the following conditions are met:
7 
8  1. Redistributions of source code must retain the above copyright notice, this
9  list of conditions and the following disclaimer.
10 
11  2. Redistributions in binary form must reproduce the above copyright notice,
12  this list of conditions and the following disclaimer in the documentation
13  and/or other materials provided with the distribution.
14 
15  3. Neither the name of the copyright holder nor the names of its contributors
16  may be used to endorse or promote products derived from this software without
17  specific prior written permission.
18 
19  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22  DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
23  FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
24  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
25  SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
26  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
27  OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
28  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
29  *******************************************************************************/
30 #include <gtest/gtest.h>
31 #include "camera_core.h" // NOLINT(build/include)
32 #include <string> // Added to satisfy roslint
33 #include <vector> // Added to satisfy roslint
34 
35 using std::string;
36 using std::stringstream;
37 using std::vector;
38 
70 
71 void getMsgInfo(rs_stream stream, const sensor_msgs::ImageConstPtr &msg)
72 {
73  g_encoding_recv[stream] = msg->encoding;
74  g_width_recv[stream] = msg->width;
75  g_height_recv[stream] = msg->height;
76  g_step_recv[stream] = msg->step;
77 }
78 
79 void getCameraInfo(rs_stream stream, const sensor_msgs::CameraInfoConstPtr &info_msg)
80 {
81  g_caminfo_height_recv[stream] = info_msg->height;
82  g_caminfo_width_recv[stream] = info_msg->width;
83 
84  g_dmodel_recv[stream] = info_msg->distortion_model;
85 
86  // copy rotation matrix
87  for (unsigned int i = 0; i < sizeof(info_msg->R)/sizeof(double); i++)
88  {
89  g_caminfo_rotation_recv[stream][i] = info_msg->R[i];
90  }
91 
92  // copy projection matrix
93  for (unsigned int i = 0; i < sizeof(info_msg->P)/sizeof(double); i++)
94  {
95  g_caminfo_projection_recv[stream][i] = info_msg->P[i];
96  }
97 }
98 
99 void imageInfrared1Callback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
100 {
102 
103  uchar *infrared1_data = image.data;
104 
105  double infrared1_total = 0.0;
106  int infrared1_count = 1;
107  for (unsigned int i = 0; i < msg->height * msg->width; i++)
108  {
109  if (*infrared1_data > 0 && *infrared1_data < 255)
110  {
111  infrared1_total += *infrared1_data;
112  infrared1_count++;
113  }
114  infrared1_data++;
115  }
116  if (infrared1_count != 1)
117  {
118  g_infrared1_avg = static_cast<float>(infrared1_total / infrared1_count);
119  }
120 
123 
124  for (unsigned int i = 0; i < 5; i++)
125  {
126  g_infrared1_caminfo_D_recv[i] = info_msg->D[i];
127  }
128 
129  g_infrared1_recv = true;
130 }
131 
132 void imageInfrared2Callback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
133 {
135 
136  uchar *infrared2_data = image.data;
137 
138  double infrared2_total = 0.0;
139  int infrared2_count = 1;
140  for (unsigned int i = 0; i < msg->height * msg->width; i++)
141  {
142  if (*infrared2_data > 0 && *infrared2_data < 255)
143  {
144  infrared2_total += *infrared2_data;
145  infrared2_count++;
146  }
147  infrared2_data++;
148  }
149  if (infrared2_count != 0)
150  {
151  g_infrared2_avg = static_cast<float>(infrared2_total / infrared2_count);
152  }
153 
156 
157  for (unsigned int i = 0; i < 5; i++)
158  {
159  g_infrared2_caminfo_D_recv[i] = info_msg->D[i];
160  }
161 
162  g_infrared2_recv = true;
163 }
164 
165 void imageDepthCallback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
166 {
168  uint16_t *image_data = reinterpret_cast<uint16_t *>(image.data);
169 
170  double depth_total = 0;
171  int depth_count = 0;
172  for (unsigned int i = 0; i < msg->height * msg->width; ++i)
173  {
174  if ((0 < *image_data) && (*image_data <= g_max_z))
175  {
176  depth_total += *image_data;
177  depth_count++;
178  }
179  image_data++;
180  }
181  if (depth_count != 0)
182  {
183  g_depth_avg = static_cast<float>(depth_total / depth_count);
184  }
185 
187  getCameraInfo(RS_STREAM_DEPTH, info_msg);
188 
189  for (unsigned int i = 0; i < 5; i++)
190  {
191  g_depth_caminfo_D_recv[i] = info_msg->D[i];
192  }
193 
194  g_depth_recv = true;
195 }
196 
197 void imageColorCallback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
198 {
199  cv::Mat image = cv_bridge::toCvShare(msg, "rgb8")->image;
200 
201  uchar *color_data = image.data;
202  int64 color_total = 0;
203  int color_count = 1;
204  for (unsigned int i = 0; i < msg->height * msg->width * 3; i++)
205  {
206  if (*color_data > 0 && *color_data < 255)
207  {
208  color_total += *color_data;
209  color_count++;
210  }
211  color_data++;
212  }
213  if (color_count != 0)
214  {
215  g_color_avg = static_cast<float>(color_total / color_count);
216  }
217 
219  getCameraInfo(RS_STREAM_COLOR, info_msg);
220 
221  for (unsigned int i = 0; i < 5; i++)
222  {
223  g_color_caminfo_D_recv[i] = info_msg->D[i];
224  }
225 
226  g_color_recv = true;
227 }
228 
229 void imageFisheyeCallback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
230 {
232 
233  uchar *fisheye_data = image.data;
234 
235  double fisheye_total = 0.0;
236  int fisheye_count = 1;
237  for (unsigned int i = 0; i < msg->height * msg->width; i++)
238  {
239  if (*fisheye_data > 0 && *fisheye_data < 255)
240  {
241  fisheye_total += *fisheye_data;
242  fisheye_count++;
243  }
244  fisheye_data++;
245  }
246  if (fisheye_count != 0)
247  {
248  g_fisheye_avg = static_cast<float>(fisheye_total / fisheye_count);
249  }
250 
252  getCameraInfo(RS_STREAM_FISHEYE, info_msg);
253 
254  for (unsigned int i = 0; i < 5; i++)
255  {
256  g_fisheye_caminfo_D_recv[i] = info_msg->D[i];
257  }
258 
259  g_fisheye_recv = true;
260 }
261 
262 void imuCallback(const sensor_msgs::ImuConstPtr &imu)
263 {
264  g_imu_recv = false;
265  if (imu->angular_velocity_covariance[0] != -1.0)
266  {
267  if ((imu->angular_velocity.x != 0.0) ||
268  (imu->angular_velocity.y != 0.0) ||
269  (imu->angular_velocity.z != 0.0))
270  {
271  g_imu_recv = true;
272  }
273  }
274  else if (imu->linear_acceleration_covariance[0] != -1.0)
275  {
276  if ((imu->linear_acceleration.x != 0.000) ||
277  (imu->linear_acceleration.y != 0.000) ||
278  (imu->linear_acceleration.z != 0.000))
279  {
280  g_imu_recv = true;
281  }
282  }
283 }
284 
285 void pcCallback(const sensor_msgs::PointCloud2ConstPtr pc)
286 {
287  pcl::PointCloud < pcl::PointXYZRGB > pointcloud;
288  pcl::fromROSMsg(*pc, pointcloud);
289 
290  double pc_depth_total = 0.0;
291  int pc_depth_count = 0;
292  for (unsigned int i = 0; i < pointcloud.width * pointcloud.height; ++i)
293  {
294  pcl::PointXYZRGB point = pointcloud.points[i];
295  double pc_depth = std::ceil(point.z);
296  if ((0.0 < pc_depth) && (pc_depth <= g_max_z))
297  {
298  pc_depth_total += pc_depth;
299  pc_depth_count++;
300  }
301  }
302  if (pc_depth_count != 0)
303  {
304  g_pc_depth_avg = static_cast<float>(pc_depth_total / pc_depth_count);
305  }
306 
307  g_pc_recv = true;
308 }
309 
310 TEST(RealsenseTests, testColorStream)
311 {
312  if (g_enable_color)
313  {
314  EXPECT_GT(g_color_avg, 0);
315  EXPECT_TRUE(g_color_recv);
316 
317  if (!g_color_encoding_exp.empty ())
318  {
320  }
321  if (g_color_step_exp > 0)
322  {
324  }
325  }
326  else
327  {
328  EXPECT_FALSE(g_color_recv);
329  }
330 }
331 
332 TEST(RealsenseTests, testColorResolution)
333 {
334  if (g_enable_color)
335  {
336  if (g_color_height_exp > 0)
337  {
339  }
340  if (g_color_width_exp > 0)
341  {
343  }
344  }
345 }
346 
347 TEST(RealsenseTests, testColorCameraInfo)
348 {
349  if (g_enable_color)
350  {
351  EXPECT_EQ(g_width_recv[RS_STREAM_COLOR], g_caminfo_width_recv[RS_STREAM_COLOR]);
352  EXPECT_EQ(g_height_recv[RS_STREAM_COLOR], g_caminfo_height_recv[RS_STREAM_COLOR]);
353  EXPECT_STREQ(g_dmodel_recv[RS_STREAM_COLOR].c_str(), "plumb_bob");
354 
355  // verify rotation is equal to identity matrix
356  for (unsigned int i = 0; i < sizeof(ROTATION_IDENTITY)/sizeof(double); i++)
357  {
358  EXPECT_EQ(ROTATION_IDENTITY[i], g_caminfo_rotation_recv[RS_STREAM_COLOR][i]);
359  }
360 
361  // check projection matrix values are set
362  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_COLOR][0] != 0.0);
363  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_COLOR][1], 0.0);
364  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_COLOR][2] != 0.0);
365  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_COLOR][3], 0.0);
366  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_COLOR][4], 0.0);
367  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_COLOR][5] != 0.0);
368  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_COLOR][6] != 0.0);
369  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_COLOR][7], 0.0);
370  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_COLOR][8], 0.0);
371  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_COLOR][9], 0.0);
372  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_COLOR][10] != 0.0);
373  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_COLOR][11], 0.0);
374 
375  // R200 and ZR300 cameras have Color distortion parameters
376  if ((g_camera_type == "R200") || (g_camera_type == "ZR300"))
377  {
378  bool any_are_zero = false;
379  // Ignoring the 5th value since it always appears to be 0.0
380  for (unsigned int i = 0; i < 4; i++)
381  {
382  if (g_color_caminfo_D_recv[i] == 0.0)
383  {
384  any_are_zero = true;
385  }
386  }
387  EXPECT_FALSE(any_are_zero);
388  }
389  }
390 }
391 
392 TEST(RealsenseTests, testIsDepthStreamEnabled)
393 {
394  if (g_enable_depth)
395  {
396  EXPECT_TRUE(g_depth_recv);
397  }
398  else
399  {
400  EXPECT_FALSE(g_depth_recv);
401  }
402 }
403 
404 TEST(RealsenseTests, testDepthStream)
405 {
406  if (g_enable_depth)
407  {
408  ROS_INFO_STREAM("RealSense Camera - depth_avg: " << g_depth_avg << " mm");
409  EXPECT_GT(g_depth_avg, 0);
410  EXPECT_TRUE(g_depth_recv);
411  if (!g_depth_encoding_exp.empty ())
412  {
414  }
415  if (g_depth_step_exp > 0)
416  {
418  }
419  }
420  else
421  {
422  EXPECT_FALSE(g_depth_recv);
423  }
424 }
425 
426 TEST(RealsenseTests, testDepthResolution)
427 {
428  if (g_enable_depth)
429  {
430  if (g_depth_height_exp > 0)
431  {
433  }
434  if (g_depth_width_exp > 0)
435  {
437  }
438  }
439 }
440 
441 TEST(RealsenseTests, testDepthCameraInfo)
442 {
443  if (g_enable_depth)
444  {
445  EXPECT_EQ(g_width_recv[RS_STREAM_DEPTH], g_caminfo_width_recv[RS_STREAM_DEPTH]);
446  EXPECT_EQ(g_height_recv[RS_STREAM_DEPTH], g_caminfo_height_recv[RS_STREAM_DEPTH]);
447  EXPECT_STREQ(g_dmodel_recv[RS_STREAM_DEPTH].c_str(), "plumb_bob");
448 
449  // verify rotation is equal to identity matrix
450  for (unsigned int i = 0; i < sizeof(ROTATION_IDENTITY)/sizeof(double); i++)
451  {
452  EXPECT_EQ(ROTATION_IDENTITY[i], g_caminfo_rotation_recv[RS_STREAM_DEPTH][i]);
453  }
454 
455  // check projection matrix values are set
456  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_DEPTH][0] != 0.0);
457  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_DEPTH][1], 0.0);
458  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_DEPTH][2] != 0.0);
459  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_DEPTH][3] != 0.0);
460  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_DEPTH][4], 0.0);
461  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_DEPTH][5] != 0.0);
462  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_DEPTH][6] != 0.0);
463  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_DEPTH][7] != 0.0);
464  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_DEPTH][8], 0.0);
465  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_DEPTH][9], 0.0);
466  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_DEPTH][10] != 0.0);
467  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_DEPTH][11] != 0.0);
468 
469  // F200 and SR300 cameras have Depth distortion parameters
470  if ((g_camera_type == "F200") || (g_camera_type == "SR300"))
471  {
472  bool any_are_zero = false;
473  for (unsigned int i = 0; i < 5; i++)
474  {
475  if (g_depth_caminfo_D_recv[i] == 0.0)
476  {
477  any_are_zero = true;
478  }
479  }
480  EXPECT_FALSE(any_are_zero);
481  }
482  }
483 }
484 
485 TEST(RealsenseTests, testInfrared1Stream)
486 {
487  if (g_enable_ir)
488  {
489  EXPECT_GT(g_infrared1_avg, 0);
490  EXPECT_TRUE(g_infrared1_recv);
491  if (!g_infrared1_encoding_exp.empty ())
492  {
494  }
495  if (g_infrared1_step_exp > 0)
496  {
498  }
499  }
500  else
501  {
502  EXPECT_FALSE(g_infrared1_recv);
503  }
504 }
505 
506 TEST(RealsenseTests, testInfrared1Resolution)
507 {
508  if (g_enable_ir)
509  {
510  if (g_depth_width_exp > 0)
511  {
513  }
514  if (g_depth_height_exp > 0)
515  {
517  }
518  }
519 }
520 
521 TEST(RealsenseTests, testInfrared1CameraInfo)
522 {
523  if (g_enable_ir)
524  {
525  EXPECT_EQ(g_width_recv[RS_STREAM_INFRARED], g_caminfo_width_recv[RS_STREAM_INFRARED]);
526  EXPECT_EQ(g_height_recv[RS_STREAM_INFRARED], g_caminfo_height_recv[RS_STREAM_INFRARED]);
527  EXPECT_STREQ(g_dmodel_recv[RS_STREAM_INFRARED].c_str(), "plumb_bob");
528 
529  // verify rotation is equal to identity matrix
530  for (unsigned int i = 0; i < sizeof(ROTATION_IDENTITY)/sizeof(double); i++)
531  {
532  EXPECT_EQ(ROTATION_IDENTITY[i], g_caminfo_rotation_recv[RS_STREAM_INFRARED][i]);
533  }
534 
535  // check projection matrix values are set
536  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED][0] != 0.0);
537  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED][1], 0.0);
538  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED][2] != 0.0);
539  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED][3], 0.0);
540  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED][4], 0.0);
541  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED][5] != 0.0);
542  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED][6] != 0.0);
543  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED][7], 0.0);
544  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED][8], 0.0);
545  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED][9], 0.0);
546  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED][10] != 0.0);
547  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED][11], 0.0);
548 
549  // F200 and SR300 cameras have IR distortion parameters
550  if ((g_camera_type == "F200") || (g_camera_type == "SR300"))
551  {
552  bool any_are_zero = false;
553  for (unsigned int i = 0; i < 5; i++)
554  {
555  if (g_infrared1_caminfo_D_recv[i] == 0.0)
556  {
557  any_are_zero = true;
558  }
559  }
560  EXPECT_FALSE(any_are_zero);
561  }
562  }
563 }
564 
565 TEST(RealsenseTests, testInfrared2Stream)
566 {
567  // R200 and ZR300 cameras have IR2
568  if ((g_camera_type == "R200") || (g_camera_type == "ZR300"))
569  {
570  if (g_enable_ir2)
571  {
572  EXPECT_GT(g_infrared2_avg, 0);
573  EXPECT_TRUE(g_infrared2_recv);
574  }
575  else
576  {
577  EXPECT_FALSE(g_infrared2_recv);
578  }
579  }
580 }
581 
582 TEST(RealsenseTests, testInfrared2Resolution)
583 {
584  // R200 and ZR300 cameras have IR2
585  if ((g_camera_type == "R200") || (g_camera_type == "ZR300"))
586  {
587  if (g_enable_ir2)
588  {
589  if (g_depth_width_exp > 0)
590  {
592  }
593  if (g_depth_height_exp > 0)
594  {
596  }
597  }
598  }
599 }
600 
601 TEST(RealsenseTests, testInfrared2CameraInfo)
602 {
603  // R200 and ZR300 cameras have IR2
604  if ((g_camera_type == "R200") || (g_camera_type == "ZR300"))
605  {
606  if (g_enable_ir2)
607  {
608  EXPECT_EQ(g_width_recv[RS_STREAM_INFRARED2], g_caminfo_width_recv[RS_STREAM_INFRARED2]);
609  EXPECT_EQ(g_height_recv[RS_STREAM_INFRARED2], g_caminfo_height_recv[RS_STREAM_INFRARED2]);
610  EXPECT_STREQ(g_dmodel_recv[RS_STREAM_INFRARED2].c_str(), "plumb_bob");
611 
612  // verify rotation is equal to identity matrix
613  for (unsigned int i = 0; i < sizeof(ROTATION_IDENTITY)/sizeof(double); i++)
614  {
615  EXPECT_EQ(ROTATION_IDENTITY[i], g_caminfo_rotation_recv[RS_STREAM_INFRARED2][i]);
616  }
617 
618  // check projection matrix values are set
619  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED2][0] != 0.0);
620  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED2][1], 0.0);
621  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED2][2] != 0.0);
622  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED2][3], 0.0);
623  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED2][4], 0.0);
624  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED2][5] != 0.0);
625  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED2][6] != 0.0);
626  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED2][7], 0.0);
627  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED2][8], 0.0);
628  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED2][9], 0.0);
629  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED2][10] != 0.0);
630  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED2][11], 0.0);
631  }
632  }
633 }
634 
635 TEST(RealsenseTests, testFisheyeStream)
636 {
637  if (g_enable_fisheye)
638  {
639  ROS_INFO_STREAM("RealSense Camera - fisheye_avg: " << g_fisheye_avg);
640  EXPECT_GT(g_fisheye_avg, 0);
641  EXPECT_TRUE(g_fisheye_recv);
642  }
643  else
644  {
645  EXPECT_FALSE(g_fisheye_recv);
646  }
647 }
648 
649 TEST(RealsenseTests, testFisheyeCameraInfo)
650 {
651  if (g_enable_fisheye)
652  {
653  EXPECT_EQ(g_width_recv[RS_STREAM_FISHEYE], g_caminfo_width_recv[RS_STREAM_FISHEYE]);
654  EXPECT_EQ(g_height_recv[RS_STREAM_FISHEYE], g_caminfo_height_recv[RS_STREAM_FISHEYE]);
655  EXPECT_STREQ(g_dmodel_recv[RS_STREAM_FISHEYE].c_str(), "plumb_bob");
656 
657  // verify rotation is equal to identity matrix
658  for (unsigned int i = 0; i < sizeof(ROTATION_IDENTITY)/sizeof(double); i++)
659  {
660  EXPECT_EQ(ROTATION_IDENTITY[i], g_caminfo_rotation_recv[RS_STREAM_FISHEYE][i]);
661  }
662 
663  // check projection matrix values are set
664  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_FISHEYE][0] != 0.0);
665  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_FISHEYE][1], 0.0);
666  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_FISHEYE][2] != 0.0);
667  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_FISHEYE][3], 0.0);
668  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_FISHEYE][4], 0.0);
669  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_FISHEYE][5] != 0.0);
670  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_FISHEYE][6] != 0.0);
671  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_FISHEYE][7], 0.0);
672  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_FISHEYE][8], 0.0);
673  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_FISHEYE][9], 0.0);
674  EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_FISHEYE][10] != 0.0);
675  EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_FISHEYE][11], 0.0);
676 
677  // ZR300 cameras have Fisheye distortion parameters
678  // Only the first coefficient is used/valid
679  if (g_camera_type == "ZR300")
680  {
681  bool any_are_zero = false;
682  for (unsigned int i = 0; i < 1; i++)
683  {
684  if (g_fisheye_caminfo_D_recv[i] == 0.0)
685  {
686  any_are_zero = true;
687  }
688  }
689  EXPECT_FALSE(any_are_zero);
690  }
691  }
692 }
693 
694 TEST(RealsenseTests, testImu)
695 {
696  if (g_enable_imu)
697  {
698  EXPECT_TRUE(g_imu_recv);
699  }
700  else
701  {
702  EXPECT_FALSE(g_imu_recv);
703  }
704 }
705 
706 TEST(RealsenseTests, testPointCloud)
707 {
709  {
710  ROS_INFO_STREAM("RealSense Camera - pc_depth_avg: " << g_pc_depth_avg);
711  EXPECT_GT(g_pc_depth_avg, 0);
712  EXPECT_TRUE(g_pc_recv);
713  }
714  else
715  {
716  EXPECT_FALSE(g_pc_recv);
717  }
718 }
719 
720 TEST(RealsenseTests, testTransforms)
721 {
722  // make sure all transforms are being broadcast as expected
723  tf::TransformListener tf_listener;
724 
726  ros::Duration(3.0)));
728  ros::Duration(3.0)));
730  ros::Duration(3.0)));
732  ros::Duration(3.0)));
734  ros::Duration(3.0)));
736  ros::Duration(3.0)));
737  if ((g_camera_type == "R200") || (g_camera_type == "ZR300"))
738  {
740  ros::Duration(3.0)));
742  ros::Duration(3.0)));
743  }
744  if (g_camera_type == "ZR300")
745  {
747  ros::Duration(3.0)));
749  ros::Duration(3.0)));
751  ros::Duration(3.0)));
753  ros::Duration(3.0)));
754  }
755 }
756 
757 TEST(RealsenseTests, testCameraOptions)
758 {
760  stringstream settings_ss(g_setting_srv.response.configuration_str);
761  string setting;
762  string setting_name;
763  string setting_value;
764 
765  while (getline (settings_ss, setting, ';'))
766  {
767  stringstream setting_ss(setting);
768  getline(setting_ss, setting_name, ':');
769  setting_value = (setting.substr(setting.rfind(":") + 1));
770  if (g_config_args.find(setting_name) != g_config_args.end())
771  {
772  int option_recv = atoi(setting_value.c_str());
773  int option_exp = atoi(g_config_args.at(setting_name).c_str());
774  EXPECT_EQ(option_exp, option_recv) << setting_name;
775  }
776  }
777 }
778 
779 TEST(RealsenseTests, testGetSettingsService)
780 {
781  // Verify the service is available
783 }
784 
785 TEST(RealsenseTests, testSetPowerOffService)
786 {
787  g_setpower_srv.request.power_on = false;
788 
790  ros::Duration(5).sleep();
791 
792  EXPECT_FALSE(g_setpower_srv.response.success);
793 }
794 
795 TEST(RealsenseTests, testSetPowerOnService)
796 {
797  g_setpower_srv.request.power_on = true;
798 
800  ros::Duration(5).sleep();
801 
802  EXPECT_TRUE(g_setpower_srv.response.success);
803 }
804 
805 TEST(RealsenseTests, testForcePowerOffService)
806 {
807  g_forcepower_srv.request.power_on = false;
808 
810  ros::Duration(5).sleep();
811 }
812 
813 TEST(RealsenseTests, testIsPoweredService)
814 {
816  EXPECT_FALSE(g_ispowered_srv.response.is_powered);
817 }
818 
819 
820 TEST(RealsenseTests, testForcePowerOnService)
821 {
822  g_forcepower_srv.request.power_on = true;
823 
825  ros::Duration(5).sleep();
826 }
827 
828 void fillConfigMap(int argc, char **argv)
829 {
830  std::vector<std::string> args;
831 
832  for (int i = 1; i < argc; ++i)
833  {
834  args.push_back(argv[i]);
835  }
836  while (args.size() > 1)
837  {
838  g_config_args[args[0]] = args[1];
839 
840  args.erase(args.begin());
841  args.erase(args.begin());
842  }
843 
844  if (argc > 1)
845  {
846  if (g_config_args.find("camera_type") != g_config_args.end())
847  {
848  ROS_INFO("RealSense Camera - Setting %s to %s", "camera_type", g_config_args.at("camera_type").c_str());
849  g_camera_type = g_config_args.at("camera_type").c_str();
850  }
851 
852  // Set depth arguments.
853  if (g_config_args.find("enable_depth") != g_config_args.end())
854  {
855  ROS_INFO("RealSense Camera - Setting %s to %s", "enable_depth", g_config_args.at("enable_depth").c_str());
856  if (strcmp((g_config_args.at("enable_depth").c_str ()), "true") == 0)
857  {
858  g_enable_depth = true;
859  }
860  else
861  {
862  g_enable_depth = false;
863  }
864  }
865 
866  // Set infrared arguments.
867  if (g_config_args.find("enable_ir") != g_config_args.end())
868  {
869  ROS_INFO("RealSense Camera - Setting %s to %s", "enable_ir", g_config_args.at("enable_ir").c_str());
870  if (strcmp((g_config_args.at("enable_ir").c_str ()), "true") == 0)
871  {
872  g_enable_ir = true;
873  }
874  else
875  {
876  g_enable_ir = false;
877  }
878  }
879 
880  // Set infrared2 arguments.
881  if (g_config_args.find("enable_ir2") != g_config_args.end())
882  {
883  ROS_INFO("RealSense Camera - Setting %s to %s", "enable_ir2", g_config_args.at("enable_ir2").c_str());
884  if (strcmp((g_config_args.at("enable_ir2").c_str ()), "true") == 0)
885  {
886  g_enable_ir2 = true;
887  }
888  else
889  {
890  g_enable_ir2 = false;
891  }
892  }
893 
894  if (g_config_args.find("depth_encoding") != g_config_args.end())
895  {
896  ROS_INFO("RealSense Camera - Setting %s to %s", "depth_encoding", g_config_args.at("depth_encoding").c_str());
897  g_depth_encoding_exp = g_config_args.at("depth_encoding").c_str();
898  }
899  if (g_config_args.find("depth_height") != g_config_args.end())
900  {
901  ROS_INFO("RealSense Camera - Setting %s to %s", "depth_height", g_config_args.at("depth_height").c_str());
902  g_depth_height_exp = atoi(g_config_args.at("depth_height").c_str());
903  }
904  if (g_config_args.find("depth_width") != g_config_args.end())
905  {
906  ROS_INFO("RealSense Camera - Setting %s to %s", "depth_width", g_config_args.at("depth_width").c_str());
907  g_depth_width_exp = atoi(g_config_args.at("depth_width").c_str());
908  }
909  if (g_config_args.find("depth_step") != g_config_args.end())
910  {
911  ROS_INFO("RealSense Camera - Setting %s to %s", "depth_step", g_config_args.at("depth_step").c_str());
912  g_depth_step_exp = atoi(g_config_args.at("depth_step").c_str());
913  }
914 
915  // Set color arguments.
916  if (g_config_args.find("enable_color") != g_config_args.end())
917  {
918  ROS_INFO("RealSense Camera - Setting %s to %s", "enable_color", g_config_args.at("enable_color").c_str());
919  if (strcmp((g_config_args.at("enable_color").c_str ()), "true") == 0)
920  {
921  g_enable_color = true;
922  }
923  else
924  {
925  g_enable_color = false;
926  }
927  }
928  if (g_config_args.find("color_encoding") != g_config_args.end())
929  {
930  ROS_INFO("RealSense Camera - Setting %s to %s", "color_encoding", g_config_args.at("color_encoding").c_str());
931  g_color_encoding_exp = g_config_args.at("color_encoding").c_str();
932  }
933  if (g_config_args.find("color_height") != g_config_args.end())
934  {
935  ROS_INFO("RealSense Camera - Setting %s to %s", "color_height", g_config_args.at("color_height").c_str());
936  g_color_height_exp = atoi(g_config_args.at("color_height").c_str());
937  }
938  if (g_config_args.find("color_width") != g_config_args.end())
939  {
940  ROS_INFO("RealSense Camera - Setting %s to %s", "color_width", g_config_args.at("color_width").c_str());
941  g_color_width_exp = atoi(g_config_args.at("color_width").c_str());
942  }
943  if (g_config_args.find("color_step") != g_config_args.end())
944  {
945  ROS_INFO("RealSense Camera - Setting %s to %s", "color_step", g_config_args.at("color_step").c_str());
946  g_color_step_exp = atoi(g_config_args.at("color_step").c_str());
947  }
948 
949  // Set fisheye arguments.
950  if (g_config_args.find("enable_fisheye") != g_config_args.end())
951  {
952  ROS_INFO("RealSense Camera - Setting %s to %s", "enable_fisheye",
953  g_config_args.at("enable_fisheye").c_str());
954  if (strcmp((g_config_args.at("enable_fisheye").c_str()), "true") == 0)
955  {
956  g_enable_fisheye = true;
957  }
958  else
959  {
960  g_enable_fisheye = false;
961  }
962  }
963 
964  // Set imu arguments.
965  if (g_config_args.find("enable_imu") != g_config_args.end())
966  {
967  ROS_INFO("RealSense Camera - Setting %s to %s", "enable_imu",
968  g_config_args.at("enable_imu").c_str());
969  if (strcmp((g_config_args.at("enable_imu").c_str()), "true") == 0)
970  {
971  g_enable_imu = true;
972  }
973  else
974  {
975  g_enable_imu = false;
976  }
977  }
978 
979  // Set pointcloud arguments.
980  if (g_config_args.find("enable_pointcloud") != g_config_args.end())
981  {
982  ROS_INFO("RealSense Camera - Setting %s to %s", "enable_pointcloud",
983  g_config_args.at("enable_pointcloud").c_str());
984  if (strcmp((g_config_args.at("enable_pointcloud").c_str()), "true") == 0)
985  {
986  g_enable_pointcloud = true;
987  }
988  else
989  {
990  g_enable_pointcloud = false;
991  }
992  }
993  }
994 }
995 
996 int main(int argc, char **argv) try
997 {
998  testing::InitGoogleTest(&argc, argv);
999  ros::init(argc, argv, "utest");
1000  fillConfigMap(argc, argv);
1001 
1002  ROS_INFO_STREAM("RealSense Camera - Starting Tests...");
1003 
1004  ros::NodeHandle nh_base;
1005  ros::NodeHandle nh(nh_base, "camera");
1006  ros::NodeHandle depth_nh(nh, DEPTH_NAMESPACE);
1007  image_transport::ImageTransport depth_image_transport(depth_nh);
1008  g_camera_subscriber[0] = depth_image_transport.subscribeCamera(DEPTH_TOPIC, 1, imageDepthCallback, 0);
1009 
1010  ros::NodeHandle color_nh(nh, COLOR_NAMESPACE);
1011  image_transport::ImageTransport color_image_transport(color_nh);
1012  g_camera_subscriber[1] = color_image_transport.subscribeCamera(COLOR_TOPIC, 1, imageColorCallback, 0);
1013 
1014  ros::NodeHandle ir_nh(nh, IR_NAMESPACE);
1015  image_transport::ImageTransport ir_image_transport(ir_nh);
1016  g_camera_subscriber[2] = ir_image_transport.subscribeCamera(IR_TOPIC, 1, imageInfrared1Callback, 0);
1017 
1018  // R200 and ZR300 cameras have IR2
1019  if ((g_camera_type == "R200") || (g_camera_type == "ZR300"))
1020  {
1021  ros::NodeHandle ir2_nh(nh, IR2_NAMESPACE);
1022  image_transport::ImageTransport ir2_image_transport(ir2_nh);
1023  g_camera_subscriber[3] = ir2_image_transport.subscribeCamera(IR2_TOPIC, 1, imageInfrared2Callback, 0);
1024  }
1025 
1026  // ZR300 cameras have Fisheye and IMU
1027  if (g_camera_type == "ZR300")
1028  {
1029  ros::NodeHandle fisheye_nh(nh, FISHEYE_NAMESPACE);
1030  image_transport::ImageTransport fisheye_image_transport(fisheye_nh);
1031  g_camera_subscriber[4] = fisheye_image_transport.subscribeCamera(FISHEYE_TOPIC, 1, imageFisheyeCallback, 0);
1032 
1033  ros::NodeHandle imu_nh(nh, IMU_NAMESPACE);
1034  g_sub_imu = imu_nh.subscribe<sensor_msgs::Imu>(IMU_TOPIC, 1, imuCallback);
1035  }
1036 
1037  g_sub_pc = depth_nh.subscribe <sensor_msgs::PointCloud2> (PC_TOPIC, 1, pcCallback);
1039  nh.serviceClient<realsense_camera::CameraConfiguration>("/camera/driver/" + SETTINGS_SERVICE);
1041  nh.serviceClient<realsense_camera::IsPowered>("/camera/driver/" + CAMERA_IS_POWERED_SERVICE);
1043  nh.serviceClient<realsense_camera::SetPower>("/camera/driver/" + CAMERA_SET_POWER_SERVICE);
1045  nh.serviceClient<realsense_camera::ForcePower>("/camera/driver/" + CAMERA_FORCE_POWER_SERVICE);
1046 
1047  ros::Duration duration;
1048  duration.sec = 10;
1049  duration.sleep();
1050  ros::spinOnce();
1051 
1052  return RUN_ALL_TESTS();
1053 }
1054 catch(...) {} // catch the "testing::internal::<unnamed>::ClassUniqueToAlwaysTrue" from gtest
RS_STREAM_INFRARED2
bool g_pc_recv
Definition: camera_core.h:109
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
const std::string PC_TOPIC
Definition: constants.h:73
const std::string DEFAULT_IR_FRAME_ID
Definition: constants.h:67
std::string g_depth_encoding_exp
Definition: camera_core.h:87
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
float g_pc_depth_avg
Definition: camera_core.h:116
ros::ServiceClient g_ispowered_srv_client
Definition: camera_core.h:96
realsense_camera::IsPowered g_ispowered_srv
Definition: camera_core.h:139
uint32_t g_step_recv[STREAM_COUNT]
Definition: camera_core.h:120
std::string g_camera_type
Definition: camera_core.h:136
int g_color_width_exp
Definition: camera_core.h:72
const std::string DEFAULT_DEPTH_FRAME_ID
Definition: constants.h:65
void imageDepthCallback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
double g_caminfo_rotation_recv[STREAM_COUNT][9]
Definition: camera_core.h:132
bool g_infrared2_recv
Definition: camera_core.h:106
double g_depth_caminfo_D_recv[5]
Definition: camera_core.h:127
image_transport::CameraSubscriber g_camera_subscriber[STREAM_COUNT]
Definition: camera_core.h:91
const std::string COLOR_NAMESPACE
Definition: constants.h:74
uint32_t g_depth_step_exp
Definition: camera_core.h:75
const std::string FISHEYE_NAMESPACE
Definition: constants.h:114
const std::string IMU_NAMESPACE
Definition: constants.h:116
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
CameraSubscriber subscribeCamera(const std::string &base_topic, uint32_t queue_size, const CameraSubscriber::Callback &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
const std::string DEFAULT_COLOR_FRAME_ID
Definition: constants.h:66
const std::string DEFAULT_FISHEYE_FRAME_ID
Definition: constants.h:119
GLenum GLenum GLsizei void * image
void fillConfigMap(int argc, char **argv)
double g_caminfo_projection_recv[STREAM_COUNT][12]
Definition: camera_core.h:133
realsense_camera::SetPower g_setpower_srv
Definition: camera_core.h:140
bool sleep() const
ros::Subscriber g_sub_pc
Definition: camera_core.h:93
const std::string CAMERA_IS_POWERED_SERVICE
Definition: constants.h:79
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
void imageColorCallback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
int g_caminfo_height_recv[STREAM_COUNT]
Definition: camera_core.h:124
const std::string DEFAULT_IR_OPTICAL_FRAME_ID
Definition: constants.h:70
const std::string TYPE_8UC1
std::string g_encoding_recv[STREAM_COUNT]
Definition: camera_core.h:122
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ros::ServiceClient g_settings_srv_client
Definition: camera_core.h:95
bool g_enable_pointcloud
Definition: camera_core.h:83
realsense_camera::ForcePower g_forcepower_srv
Definition: camera_core.h:141
float g_color_avg
Definition: camera_core.h:112
bool g_depth_recv
Definition: camera_core.h:103
float g_depth_avg
Definition: camera_core.h:111
int g_caminfo_width_recv[STREAM_COUNT]
Definition: camera_core.h:125
void getMsgInfo(rs_stream stream, const sensor_msgs::ImageConstPtr &msg)
Definition: camera_core.cpp:71
bool g_enable_imu
Definition: camera_core.h:82
ros::Subscriber g_sub_imu
Definition: camera_core.h:92
double g_color_caminfo_D_recv[5]
Definition: camera_core.h:126
TEST(RealsenseTests, testColorStream)
double g_max_z
Definition: camera_core.h:101
uint32_t g_infrared1_step_exp
Definition: camera_core.h:77
void imageFisheyeCallback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
bool g_infrared1_recv
Definition: camera_core.h:105
ros::ServiceClient g_forcepower_srv_client
Definition: camera_core.h:98
void imageInfrared2Callback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
double g_fisheye_caminfo_D_recv[5]
Definition: camera_core.h:130
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
float g_fisheye_avg
Definition: camera_core.h:115
const std::string FISHEYE_TOPIC
Definition: constants.h:115
std::string g_color_encoding_exp
Definition: camera_core.h:88
const std::string IR2_TOPIC
Definition: constants.h:89
void getCameraInfo(rs_stream stream, const sensor_msgs::CameraInfoConstPtr &info_msg)
Definition: camera_core.cpp:79
const std::string DEFAULT_IMU_OPTICAL_FRAME_ID
Definition: constants.h:122
stream
bool g_enable_color
Definition: camera_core.h:79
const std::string DEFAULT_COLOR_OPTICAL_FRAME_ID
Definition: constants.h:69
bool g_imu_recv
Definition: camera_core.h:108
const std::string IR2_NAMESPACE
Definition: constants.h:88
int main(int argc, char **argv)
#define ROS_INFO(...)
float g_infrared1_avg
Definition: camera_core.h:113
realsense_camera::CameraConfiguration g_setting_srv
Definition: camera_core.h:138
uint32_t g_color_step_exp
Definition: camera_core.h:76
std::map< std::string, std::string > g_config_args
Definition: camera_core.h:100
const std::string IR_TOPIC
Definition: constants.h:77
const std::string DEFAULT_IMU_FRAME_ID
Definition: constants.h:120
const std::string TYPE_16UC1
int g_depth_height_exp
Definition: camera_core.h:73
const std::string COLOR_TOPIC
Definition: constants.h:75
const std::string IMU_TOPIC
Definition: constants.h:117
const std::string DEFAULT_BASE_FRAME_ID
Definition: constants.h:64
float g_infrared2_avg
Definition: camera_core.h:114
void imageInfrared1Callback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
Definition: camera_core.cpp:99
int g_height_recv[STREAM_COUNT]
Definition: camera_core.h:118
const std::string DEPTH_TOPIC
Definition: constants.h:72
const std::string DEFAULT_DEPTH_OPTICAL_FRAME_ID
Definition: constants.h:68
const std::string DEPTH_NAMESPACE
Definition: constants.h:71
const double ROTATION_IDENTITY[]
Definition: constants.h:84
bool g_fisheye_recv
Definition: camera_core.h:107
#define ROS_INFO_STREAM(args)
rs_stream
const std::string DEFAULT_IR2_FRAME_ID
Definition: constants.h:90
const std::string DEFAULT_IR2_OPTICAL_FRAME_ID
Definition: constants.h:91
const std::string IR_NAMESPACE
Definition: constants.h:76
bool g_color_recv
Definition: camera_core.h:104
void pcCallback(const sensor_msgs::PointCloud2ConstPtr pc)
const std::string CAMERA_FORCE_POWER_SERVICE
Definition: constants.h:81
int g_color_height_exp
Definition: camera_core.h:71
ros::ServiceClient g_setpower_srv_client
Definition: camera_core.h:97
bool g_enable_fisheye
Definition: camera_core.h:81
void imuCallback(const sensor_msgs::ImuConstPtr &imu)
std::string g_dmodel_recv[STREAM_COUNT]
Definition: camera_core.h:135
const std::string CAMERA_SET_POWER_SERVICE
Definition: constants.h:80
RS_STREAM_FISHEYE
RS_STREAM_DEPTH
const std::string SETTINGS_SERVICE
Definition: constants.h:78
std::string g_infrared1_encoding_exp
Definition: camera_core.h:89
ROSCPP_DECL void spinOnce()
double g_infrared1_caminfo_D_recv[5]
Definition: camera_core.h:128
const std::string DEFAULT_FISHEYE_OPTICAL_FRAME_ID
Definition: constants.h:121
RS_STREAM_INFRARED
double g_infrared2_caminfo_D_recv[5]
Definition: camera_core.h:129
bool g_enable_depth
Definition: camera_core.h:80
RS_STREAM_COLOR
bool g_enable_ir
Definition: camera_core.h:84
int g_depth_width_exp
Definition: camera_core.h:74
int g_width_recv[STREAM_COUNT]
Definition: camera_core.h:119
bool g_enable_ir2
Definition: camera_core.h:85


realsense_camera
Author(s): Rajvi Jingar , Reagan Lopez , Matt Hansen , Mark Horn
autogenerated on Mon Jun 10 2019 14:40:37