camera_core.cpp
Go to the documentation of this file.
00001 /******************************************************************************
00002  Copyright (c) 2016, Intel Corporation
00003  All rights reserved.
00004 
00005  Redistribution and use in source and binary forms, with or without
00006  modification, are permitted provided that the following conditions are met:
00007 
00008  1. Redistributions of source code must retain the above copyright notice, this
00009  list of conditions and the following disclaimer.
00010 
00011  2. Redistributions in binary form must reproduce the above copyright notice,
00012  this list of conditions and the following disclaimer in the documentation
00013  and/or other materials provided with the distribution.
00014 
00015  3. Neither the name of the copyright holder nor the names of its contributors
00016  may be used to endorse or promote products derived from this software without
00017  specific prior written permission.
00018 
00019  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00020  AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00021  IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00022  DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
00023  FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00024  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00025  SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00026  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
00027  OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
00028  OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00029  *******************************************************************************/
00030 #include <gtest/gtest.h>
00031 #include "camera_core.h"  // NOLINT(build/include)
00032 #include <string>  // Added to satisfy roslint
00033 #include <vector>  // Added to satisfy roslint
00034 
00035 using std::string;
00036 using std::stringstream;
00037 using std::vector;
00038 
00039 using realsense_camera::CAMERA_FORCE_POWER_SERVICE;
00040 using realsense_camera::CAMERA_IS_POWERED_SERVICE;
00041 using realsense_camera::CAMERA_SET_POWER_SERVICE;
00042 using realsense_camera::COLOR_NAMESPACE;
00043 using realsense_camera::COLOR_TOPIC;
00044 using realsense_camera::DEFAULT_BASE_FRAME_ID;
00045 using realsense_camera::DEFAULT_COLOR_FRAME_ID;
00046 using realsense_camera::DEFAULT_COLOR_OPTICAL_FRAME_ID;
00047 using realsense_camera::DEFAULT_DEPTH_FRAME_ID;
00048 using realsense_camera::DEFAULT_DEPTH_OPTICAL_FRAME_ID;
00049 using realsense_camera::DEFAULT_FISHEYE_FRAME_ID;
00050 using realsense_camera::DEFAULT_FISHEYE_OPTICAL_FRAME_ID;
00051 using realsense_camera::DEFAULT_IMU_FRAME_ID;
00052 using realsense_camera::DEFAULT_IMU_OPTICAL_FRAME_ID;
00053 using realsense_camera::DEFAULT_IR2_FRAME_ID;
00054 using realsense_camera::DEFAULT_IR2_OPTICAL_FRAME_ID;
00055 using realsense_camera::DEFAULT_IR_FRAME_ID;
00056 using realsense_camera::DEFAULT_IR_OPTICAL_FRAME_ID;
00057 using realsense_camera::DEPTH_NAMESPACE;
00058 using realsense_camera::DEPTH_TOPIC;
00059 using realsense_camera::FISHEYE_NAMESPACE;
00060 using realsense_camera::FISHEYE_TOPIC;
00061 using realsense_camera::IMU_NAMESPACE;
00062 using realsense_camera::IMU_TOPIC;
00063 using realsense_camera::IR2_NAMESPACE;
00064 using realsense_camera::IR2_TOPIC;
00065 using realsense_camera::IR_NAMESPACE;
00066 using realsense_camera::IR_TOPIC;
00067 using realsense_camera::PC_TOPIC;
00068 using realsense_camera::ROTATION_IDENTITY;
00069 using realsense_camera::SETTINGS_SERVICE;
00070 
00071 void getMsgInfo(rs_stream stream, const sensor_msgs::ImageConstPtr &msg)
00072 {
00073   g_encoding_recv[stream] = msg->encoding;
00074   g_width_recv[stream] = msg->width;
00075   g_height_recv[stream] = msg->height;
00076   g_step_recv[stream] = msg->step;
00077 }
00078 
00079 void getCameraInfo(rs_stream stream, const sensor_msgs::CameraInfoConstPtr &info_msg)
00080 {
00081   g_caminfo_height_recv[stream] = info_msg->height;
00082   g_caminfo_width_recv[stream] = info_msg->width;
00083 
00084   g_dmodel_recv[stream] = info_msg->distortion_model;
00085 
00086   // copy rotation matrix
00087   for (unsigned int i = 0; i < sizeof(info_msg->R)/sizeof(double); i++)
00088   {
00089     g_caminfo_rotation_recv[stream][i] = info_msg->R[i];
00090   }
00091 
00092   // copy projection matrix
00093   for (unsigned int i = 0; i < sizeof(info_msg->P)/sizeof(double); i++)
00094   {
00095     g_caminfo_projection_recv[stream][i] = info_msg->P[i];
00096   }
00097 }
00098 
00099 void imageInfrared1Callback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
00100 {
00101   cv::Mat image = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::TYPE_8UC1)->image;
00102 
00103   uchar *infrared1_data = image.data;
00104 
00105   double infrared1_total = 0.0;
00106   int infrared1_count = 1;
00107   for (unsigned int i = 0; i < msg->height * msg->width; i++)
00108   {
00109     if (*infrared1_data > 0 && *infrared1_data < 255)
00110     {
00111       infrared1_total += *infrared1_data;
00112       infrared1_count++;
00113     }
00114     infrared1_data++;
00115   }
00116   if (infrared1_count != 1)
00117   {
00118     g_infrared1_avg = static_cast<float>(infrared1_total / infrared1_count);
00119   }
00120 
00121   getMsgInfo(RS_STREAM_INFRARED, msg);
00122   getCameraInfo(RS_STREAM_INFRARED, info_msg);
00123 
00124   for (unsigned int i = 0; i < 5; i++)
00125   {
00126     g_infrared1_caminfo_D_recv[i] = info_msg->D[i];
00127   }
00128 
00129   g_infrared1_recv = true;
00130 }
00131 
00132 void imageInfrared2Callback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
00133 {
00134   cv::Mat image = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::TYPE_8UC1)->image;
00135 
00136   uchar *infrared2_data = image.data;
00137 
00138   double infrared2_total = 0.0;
00139   int infrared2_count = 1;
00140   for (unsigned int i = 0; i < msg->height * msg->width; i++)
00141   {
00142     if (*infrared2_data > 0 && *infrared2_data < 255)
00143     {
00144       infrared2_total += *infrared2_data;
00145       infrared2_count++;
00146     }
00147     infrared2_data++;
00148   }
00149   if (infrared2_count != 0)
00150   {
00151     g_infrared2_avg = static_cast<float>(infrared2_total / infrared2_count);
00152   }
00153 
00154   getMsgInfo(RS_STREAM_INFRARED2, msg);
00155   getCameraInfo(RS_STREAM_INFRARED2, info_msg);
00156 
00157   for (unsigned int i = 0; i < 5; i++)
00158   {
00159     g_infrared2_caminfo_D_recv[i] = info_msg->D[i];
00160   }
00161 
00162   g_infrared2_recv = true;
00163 }
00164 
00165 void imageDepthCallback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
00166 {
00167   cv::Mat image = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::TYPE_16UC1)->image;
00168   uint16_t *image_data = reinterpret_cast<uint16_t *>(image.data);
00169 
00170   double depth_total = 0;
00171   int depth_count = 0;
00172   for (unsigned int i = 0; i < msg->height * msg->width; ++i)
00173   {
00174     if ((0 < *image_data) && (*image_data <= g_max_z))
00175     {
00176       depth_total += *image_data;
00177       depth_count++;
00178     }
00179     image_data++;
00180   }
00181   if (depth_count != 0)
00182   {
00183     g_depth_avg = static_cast<float>(depth_total / depth_count);
00184   }
00185 
00186   getMsgInfo(RS_STREAM_DEPTH, msg);
00187   getCameraInfo(RS_STREAM_DEPTH, info_msg);
00188 
00189   for (unsigned int i = 0; i < 5; i++)
00190   {
00191     g_depth_caminfo_D_recv[i] = info_msg->D[i];
00192   }
00193 
00194   g_depth_recv = true;
00195 }
00196 
00197 void imageColorCallback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
00198 {
00199   cv::Mat image = cv_bridge::toCvShare(msg, "rgb8")->image;
00200 
00201   uchar *color_data = image.data;
00202   int64 color_total = 0;
00203   int color_count = 1;
00204   for (unsigned int i = 0; i < msg->height * msg->width * 3; i++)
00205   {
00206     if (*color_data > 0 && *color_data < 255)
00207     {
00208       color_total += *color_data;
00209       color_count++;
00210     }
00211     color_data++;
00212   }
00213   if (color_count != 0)
00214   {
00215     g_color_avg = static_cast<float>(color_total / color_count);
00216   }
00217 
00218   getMsgInfo(RS_STREAM_COLOR, msg);
00219   getCameraInfo(RS_STREAM_COLOR, info_msg);
00220 
00221   for (unsigned int i = 0; i < 5; i++)
00222   {
00223     g_color_caminfo_D_recv[i] = info_msg->D[i];
00224   }
00225 
00226   g_color_recv = true;
00227 }
00228 
00229 void imageFisheyeCallback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
00230 {
00231   cv::Mat image = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::TYPE_8UC1)->image;
00232 
00233   uchar *fisheye_data = image.data;
00234 
00235   double fisheye_total = 0.0;
00236   int fisheye_count = 1;
00237   for (unsigned int i = 0; i < msg->height * msg->width; i++)
00238   {
00239     if (*fisheye_data > 0 && *fisheye_data < 255)
00240     {
00241       fisheye_total += *fisheye_data;
00242       fisheye_count++;
00243     }
00244     fisheye_data++;
00245   }
00246   if (fisheye_count != 0)
00247   {
00248     g_fisheye_avg = static_cast<float>(fisheye_total / fisheye_count);
00249   }
00250 
00251   getMsgInfo(RS_STREAM_FISHEYE, msg);
00252   getCameraInfo(RS_STREAM_FISHEYE, info_msg);
00253 
00254   for (unsigned int i = 0; i < 5; i++)
00255   {
00256     g_fisheye_caminfo_D_recv[i] = info_msg->D[i];
00257   }
00258 
00259   g_fisheye_recv = true;
00260 }
00261 
00262 void imuCallback(const sensor_msgs::ImuConstPtr &imu)
00263 {
00264   g_imu_recv = false;
00265   if (imu->angular_velocity_covariance[0] != -1.0)
00266   {
00267     if ((imu->angular_velocity.x != 0.0) ||
00268         (imu->angular_velocity.y != 0.0) ||
00269         (imu->angular_velocity.z != 0.0))
00270     {
00271       g_imu_recv = true;
00272     }
00273   }
00274   else if (imu->linear_acceleration_covariance[0] != -1.0)
00275   {
00276     if ((imu->linear_acceleration.x != 0.000) ||
00277         (imu->linear_acceleration.y != 0.000) ||
00278         (imu->linear_acceleration.z != 0.000))
00279     {
00280       g_imu_recv = true;
00281     }
00282   }
00283 }
00284 
00285 void pcCallback(const sensor_msgs::PointCloud2ConstPtr pc)
00286 {
00287   pcl::PointCloud < pcl::PointXYZRGB > pointcloud;
00288   pcl::fromROSMsg(*pc, pointcloud);
00289 
00290   double pc_depth_total = 0.0;
00291   int pc_depth_count = 0;
00292   for (unsigned int i = 0; i < pointcloud.width * pointcloud.height; ++i)
00293   {
00294     pcl::PointXYZRGB point = pointcloud.points[i];
00295     double pc_depth = std::ceil(point.z);
00296     if ((0.0 < pc_depth) && (pc_depth <= g_max_z))
00297     {
00298       pc_depth_total += pc_depth;
00299       pc_depth_count++;
00300     }
00301   }
00302   if (pc_depth_count != 0)
00303   {
00304     g_pc_depth_avg = static_cast<float>(pc_depth_total / pc_depth_count);
00305   }
00306 
00307   g_pc_recv = true;
00308 }
00309 
00310 TEST(RealsenseTests, testColorStream)
00311 {
00312   if (g_enable_color)
00313   {
00314     EXPECT_GT(g_color_avg, 0);
00315     EXPECT_TRUE(g_color_recv);
00316 
00317     if (!g_color_encoding_exp.empty ())
00318     {
00319       EXPECT_EQ(g_color_encoding_exp, g_encoding_recv[RS_STREAM_COLOR]);
00320     }
00321     if (g_color_step_exp > 0)
00322     {
00323       EXPECT_EQ(g_color_step_exp, g_step_recv[RS_STREAM_COLOR]);
00324     }
00325   }
00326   else
00327   {
00328     EXPECT_FALSE(g_color_recv);
00329   }
00330 }
00331 
00332 TEST(RealsenseTests, testColorResolution)
00333 {
00334   if (g_enable_color)
00335   {
00336     if (g_color_height_exp > 0)
00337     {
00338       EXPECT_EQ(g_color_height_exp, g_height_recv[RS_STREAM_COLOR]);
00339     }
00340     if (g_color_width_exp > 0)
00341     {
00342       EXPECT_EQ(g_color_width_exp, g_width_recv[RS_STREAM_COLOR]);
00343     }
00344   }
00345 }
00346 
00347 TEST(RealsenseTests, testColorCameraInfo)
00348 {
00349   if (g_enable_color)
00350   {
00351     EXPECT_EQ(g_width_recv[RS_STREAM_COLOR], g_caminfo_width_recv[RS_STREAM_COLOR]);
00352     EXPECT_EQ(g_height_recv[RS_STREAM_COLOR], g_caminfo_height_recv[RS_STREAM_COLOR]);
00353     EXPECT_STREQ(g_dmodel_recv[RS_STREAM_COLOR].c_str(), "plumb_bob");
00354 
00355     // verify rotation is equal to identity matrix
00356     for (unsigned int i = 0; i < sizeof(ROTATION_IDENTITY)/sizeof(double); i++)
00357     {
00358       EXPECT_EQ(ROTATION_IDENTITY[i], g_caminfo_rotation_recv[RS_STREAM_COLOR][i]);
00359     }
00360 
00361     // check projection matrix values are set
00362     EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_COLOR][0] != 0.0);
00363     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_COLOR][1], 0.0);
00364     EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_COLOR][2] != 0.0);
00365     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_COLOR][3], 0.0);
00366     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_COLOR][4], 0.0);
00367     EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_COLOR][5] != 0.0);
00368     EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_COLOR][6] != 0.0);
00369     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_COLOR][7], 0.0);
00370     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_COLOR][8], 0.0);
00371     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_COLOR][9], 0.0);
00372     EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_COLOR][10] != 0.0);
00373     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_COLOR][11], 0.0);
00374 
00375     // R200 and ZR300 cameras have Color distortion parameters
00376     if ((g_camera_type == "R200") || (g_camera_type == "ZR300"))
00377     {
00378       bool any_are_zero = false;
00379       // Ignoring the 5th value since it always appears to be 0.0
00380       for (unsigned int i = 0; i < 4; i++)
00381       {
00382         if (g_color_caminfo_D_recv[i] == 0.0)
00383         {
00384           any_are_zero = true;
00385         }
00386       }
00387       EXPECT_FALSE(any_are_zero);
00388     }
00389   }
00390 }
00391 
00392 TEST(RealsenseTests, testIsDepthStreamEnabled)
00393 {
00394   if (g_enable_depth)
00395   {
00396     EXPECT_TRUE(g_depth_recv);
00397   }
00398   else
00399   {
00400     EXPECT_FALSE(g_depth_recv);
00401   }
00402 }
00403 
00404 TEST(RealsenseTests, testDepthStream)
00405 {
00406   if (g_enable_depth)
00407   {
00408     ROS_INFO_STREAM("RealSense Camera - depth_avg: " << g_depth_avg << " mm");
00409     EXPECT_GT(g_depth_avg, 0);
00410     EXPECT_TRUE(g_depth_recv);
00411     if (!g_depth_encoding_exp.empty ())
00412     {
00413       EXPECT_EQ(g_depth_encoding_exp, g_encoding_recv[RS_STREAM_DEPTH]);
00414     }
00415     if (g_depth_step_exp > 0)
00416     {
00417       EXPECT_EQ(g_depth_step_exp, g_step_recv[RS_STREAM_DEPTH]);
00418     }
00419   }
00420   else
00421   {
00422     EXPECT_FALSE(g_depth_recv);
00423   }
00424 }
00425 
00426 TEST(RealsenseTests, testDepthResolution)
00427 {
00428   if (g_enable_depth)
00429   {
00430     if (g_depth_height_exp > 0)
00431     {
00432       EXPECT_EQ(g_depth_height_exp, g_height_recv[RS_STREAM_DEPTH]);
00433     }
00434     if (g_depth_width_exp > 0)
00435     {
00436       EXPECT_EQ(g_depth_width_exp, g_width_recv[RS_STREAM_DEPTH]);
00437     }
00438   }
00439 }
00440 
00441 TEST(RealsenseTests, testDepthCameraInfo)
00442 {
00443   if (g_enable_depth)
00444   {
00445     EXPECT_EQ(g_width_recv[RS_STREAM_DEPTH], g_caminfo_width_recv[RS_STREAM_DEPTH]);
00446     EXPECT_EQ(g_height_recv[RS_STREAM_DEPTH], g_caminfo_height_recv[RS_STREAM_DEPTH]);
00447     EXPECT_STREQ(g_dmodel_recv[RS_STREAM_DEPTH].c_str(), "plumb_bob");
00448 
00449     // verify rotation is equal to identity matrix
00450     for (unsigned int i = 0; i < sizeof(ROTATION_IDENTITY)/sizeof(double); i++)
00451     {
00452       EXPECT_EQ(ROTATION_IDENTITY[i], g_caminfo_rotation_recv[RS_STREAM_DEPTH][i]);
00453     }
00454 
00455     // check projection matrix values are set
00456     EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_DEPTH][0] != 0.0);
00457     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_DEPTH][1], 0.0);
00458     EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_DEPTH][2] != 0.0);
00459     EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_DEPTH][3] != 0.0);
00460     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_DEPTH][4], 0.0);
00461     EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_DEPTH][5] != 0.0);
00462     EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_DEPTH][6] != 0.0);
00463     EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_DEPTH][7] != 0.0);
00464     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_DEPTH][8], 0.0);
00465     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_DEPTH][9], 0.0);
00466     EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_DEPTH][10] != 0.0);
00467     EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_DEPTH][11] != 0.0);
00468 
00469     // F200 and SR300 cameras have Depth distortion parameters
00470     if ((g_camera_type == "F200") || (g_camera_type == "SR300"))
00471     {
00472       bool any_are_zero = false;
00473       for (unsigned int i = 0; i < 5; i++)
00474       {
00475         if (g_depth_caminfo_D_recv[i] == 0.0)
00476         {
00477           any_are_zero = true;
00478         }
00479       }
00480       EXPECT_FALSE(any_are_zero);
00481     }
00482   }
00483 }
00484 
00485 TEST(RealsenseTests, testInfrared1Stream)
00486 {
00487   if (g_enable_ir)
00488   {
00489     EXPECT_GT(g_infrared1_avg, 0);
00490     EXPECT_TRUE(g_infrared1_recv);
00491     if (!g_infrared1_encoding_exp.empty ())
00492     {
00493       EXPECT_EQ(g_infrared1_encoding_exp, g_encoding_recv[RS_STREAM_INFRARED]);
00494     }
00495     if (g_infrared1_step_exp > 0)
00496     {
00497       EXPECT_EQ(g_infrared1_step_exp, g_step_recv[RS_STREAM_INFRARED]);
00498     }
00499   }
00500   else
00501   {
00502     EXPECT_FALSE(g_infrared1_recv);
00503   }
00504 }
00505 
00506 TEST(RealsenseTests, testInfrared1Resolution)
00507 {
00508   if (g_enable_ir)
00509   {
00510     if (g_depth_width_exp > 0)
00511     {
00512       EXPECT_EQ(g_depth_width_exp, g_width_recv[RS_STREAM_INFRARED]);
00513     }
00514     if (g_depth_height_exp > 0)
00515     {
00516       EXPECT_EQ(g_depth_height_exp, g_height_recv[RS_STREAM_INFRARED]);
00517     }
00518   }
00519 }
00520 
00521 TEST(RealsenseTests, testInfrared1CameraInfo)
00522 {
00523   if (g_enable_ir)
00524   {
00525     EXPECT_EQ(g_width_recv[RS_STREAM_INFRARED], g_caminfo_width_recv[RS_STREAM_INFRARED]);
00526     EXPECT_EQ(g_height_recv[RS_STREAM_INFRARED], g_caminfo_height_recv[RS_STREAM_INFRARED]);
00527     EXPECT_STREQ(g_dmodel_recv[RS_STREAM_INFRARED].c_str(), "plumb_bob");
00528 
00529     // verify rotation is equal to identity matrix
00530     for (unsigned int i = 0; i < sizeof(ROTATION_IDENTITY)/sizeof(double); i++)
00531     {
00532       EXPECT_EQ(ROTATION_IDENTITY[i], g_caminfo_rotation_recv[RS_STREAM_INFRARED][i]);
00533     }
00534 
00535     // check projection matrix values are set
00536     EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED][0] != 0.0);
00537     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED][1], 0.0);
00538     EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED][2] != 0.0);
00539     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED][3], 0.0);
00540     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED][4], 0.0);
00541     EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED][5] != 0.0);
00542     EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED][6] != 0.0);
00543     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED][7], 0.0);
00544     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED][8], 0.0);
00545     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED][9], 0.0);
00546     EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED][10] != 0.0);
00547     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED][11], 0.0);
00548 
00549     // F200 and SR300 cameras have IR distortion parameters
00550     if ((g_camera_type == "F200") || (g_camera_type == "SR300"))
00551     {
00552       bool any_are_zero = false;
00553       for (unsigned int i = 0; i < 5; i++)
00554       {
00555         if (g_infrared1_caminfo_D_recv[i] == 0.0)
00556         {
00557           any_are_zero = true;
00558         }
00559       }
00560       EXPECT_FALSE(any_are_zero);
00561     }
00562   }
00563 }
00564 
00565 TEST(RealsenseTests, testInfrared2Stream)
00566 {
00567   // R200 and ZR300 cameras have IR2
00568   if ((g_camera_type == "R200") || (g_camera_type == "ZR300"))
00569   {
00570     if (g_enable_ir2)
00571     {
00572       EXPECT_GT(g_infrared2_avg, 0);
00573       EXPECT_TRUE(g_infrared2_recv);
00574     }
00575     else
00576     {
00577       EXPECT_FALSE(g_infrared2_recv);
00578     }
00579   }
00580 }
00581 
00582 TEST(RealsenseTests, testInfrared2Resolution)
00583 {
00584   // R200 and ZR300 cameras have IR2
00585   if ((g_camera_type == "R200") || (g_camera_type == "ZR300"))
00586   {
00587     if (g_enable_ir2)
00588     {
00589       if (g_depth_width_exp > 0)
00590       {
00591         EXPECT_EQ(g_depth_width_exp, g_width_recv[RS_STREAM_INFRARED2]);
00592       }
00593       if (g_depth_height_exp > 0)
00594       {
00595         EXPECT_EQ(g_depth_height_exp, g_height_recv[RS_STREAM_INFRARED2]);
00596       }
00597     }
00598   }
00599 }
00600 
00601 TEST(RealsenseTests, testInfrared2CameraInfo)
00602 {
00603   // R200 and ZR300 cameras have IR2
00604   if ((g_camera_type == "R200") || (g_camera_type == "ZR300"))
00605   {
00606     if (g_enable_ir2)
00607     {
00608       EXPECT_EQ(g_width_recv[RS_STREAM_INFRARED2], g_caminfo_width_recv[RS_STREAM_INFRARED2]);
00609       EXPECT_EQ(g_height_recv[RS_STREAM_INFRARED2], g_caminfo_height_recv[RS_STREAM_INFRARED2]);
00610       EXPECT_STREQ(g_dmodel_recv[RS_STREAM_INFRARED2].c_str(), "plumb_bob");
00611 
00612       // verify rotation is equal to identity matrix
00613       for (unsigned int i = 0; i < sizeof(ROTATION_IDENTITY)/sizeof(double); i++)
00614       {
00615         EXPECT_EQ(ROTATION_IDENTITY[i], g_caminfo_rotation_recv[RS_STREAM_INFRARED2][i]);
00616       }
00617 
00618       // check projection matrix values are set
00619       EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED2][0] != 0.0);
00620       EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED2][1], 0.0);
00621       EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED2][2] != 0.0);
00622       EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED2][3], 0.0);
00623       EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED2][4], 0.0);
00624       EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED2][5] != 0.0);
00625       EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED2][6] != 0.0);
00626       EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED2][7], 0.0);
00627       EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED2][8], 0.0);
00628       EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED2][9], 0.0);
00629       EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED2][10] != 0.0);
00630       EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED2][11], 0.0);
00631     }
00632   }
00633 }
00634 
00635 TEST(RealsenseTests, testFisheyeStream)
00636 {
00637   if (g_enable_fisheye)
00638   {
00639     ROS_INFO_STREAM("RealSense Camera - fisheye_avg: " << g_fisheye_avg);
00640     EXPECT_GT(g_fisheye_avg, 0);
00641     EXPECT_TRUE(g_fisheye_recv);
00642   }
00643   else
00644   {
00645     EXPECT_FALSE(g_fisheye_recv);
00646   }
00647 }
00648 
00649 TEST(RealsenseTests, testFisheyeCameraInfo)
00650 {
00651   if (g_enable_fisheye)
00652   {
00653     EXPECT_EQ(g_width_recv[RS_STREAM_FISHEYE], g_caminfo_width_recv[RS_STREAM_FISHEYE]);
00654     EXPECT_EQ(g_height_recv[RS_STREAM_FISHEYE], g_caminfo_height_recv[RS_STREAM_FISHEYE]);
00655     EXPECT_STREQ(g_dmodel_recv[RS_STREAM_FISHEYE].c_str(), "plumb_bob");
00656 
00657     // verify rotation is equal to identity matrix
00658     for (unsigned int i = 0; i < sizeof(ROTATION_IDENTITY)/sizeof(double); i++)
00659     {
00660       EXPECT_EQ(ROTATION_IDENTITY[i], g_caminfo_rotation_recv[RS_STREAM_FISHEYE][i]);
00661     }
00662 
00663     // check projection matrix values are set
00664     EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_FISHEYE][0] != 0.0);
00665     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_FISHEYE][1], 0.0);
00666     EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_FISHEYE][2] != 0.0);
00667     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_FISHEYE][3], 0.0);
00668     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_FISHEYE][4], 0.0);
00669     EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_FISHEYE][5] != 0.0);
00670     EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_FISHEYE][6] != 0.0);
00671     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_FISHEYE][7], 0.0);
00672     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_FISHEYE][8], 0.0);
00673     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_FISHEYE][9], 0.0);
00674     EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_FISHEYE][10] != 0.0);
00675     EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_FISHEYE][11], 0.0);
00676 
00677     // ZR300 cameras have Fisheye distortion parameters
00678     // Only the first coefficient is used/valid
00679     if (g_camera_type == "ZR300")
00680     {
00681       bool any_are_zero = false;
00682       for (unsigned int i = 0; i < 1; i++)
00683       {
00684         if (g_fisheye_caminfo_D_recv[i] == 0.0)
00685         {
00686           any_are_zero = true;
00687         }
00688       }
00689       EXPECT_FALSE(any_are_zero);
00690     }
00691   }
00692 }
00693 
00694 TEST(RealsenseTests, testImu)
00695 {
00696   if (g_enable_imu)
00697   {
00698     EXPECT_TRUE(g_imu_recv);
00699   }
00700   else
00701   {
00702     EXPECT_FALSE(g_imu_recv);
00703   }
00704 }
00705 
00706 TEST(RealsenseTests, testPointCloud)
00707 {
00708   if (g_enable_pointcloud)
00709   {
00710     ROS_INFO_STREAM("RealSense Camera - pc_depth_avg: " << g_pc_depth_avg);
00711     EXPECT_GT(g_pc_depth_avg, 0);
00712     EXPECT_TRUE(g_pc_recv);
00713   }
00714   else
00715   {
00716     EXPECT_FALSE(g_pc_recv);
00717   }
00718 }
00719 
00720 TEST(RealsenseTests, testTransforms)
00721 {
00722   // make sure all transforms are being broadcast as expected
00723   tf::TransformListener tf_listener;
00724 
00725   EXPECT_TRUE(tf_listener.waitForTransform(DEFAULT_DEPTH_FRAME_ID, DEFAULT_BASE_FRAME_ID, ros::Time(0),
00726       ros::Duration(3.0)));
00727   EXPECT_TRUE(tf_listener.waitForTransform(DEFAULT_DEPTH_OPTICAL_FRAME_ID, DEFAULT_DEPTH_FRAME_ID, ros::Time(0),
00728       ros::Duration(3.0)));
00729   EXPECT_TRUE(tf_listener.waitForTransform(DEFAULT_COLOR_FRAME_ID, DEFAULT_BASE_FRAME_ID, ros::Time(0),
00730       ros::Duration(3.0)));
00731   EXPECT_TRUE(tf_listener.waitForTransform(DEFAULT_COLOR_OPTICAL_FRAME_ID, DEFAULT_COLOR_FRAME_ID, ros::Time(0),
00732       ros::Duration(3.0)));
00733   EXPECT_TRUE(tf_listener.waitForTransform(DEFAULT_IR_FRAME_ID, DEFAULT_BASE_FRAME_ID, ros::Time(0),
00734       ros::Duration(3.0)));
00735   EXPECT_TRUE(tf_listener.waitForTransform(DEFAULT_IR_OPTICAL_FRAME_ID, DEFAULT_IR_FRAME_ID, ros::Time(0),
00736       ros::Duration(3.0)));
00737   if ((g_camera_type == "R200") || (g_camera_type == "ZR300"))
00738   {
00739     EXPECT_TRUE(tf_listener.waitForTransform(DEFAULT_IR2_FRAME_ID, DEFAULT_BASE_FRAME_ID, ros::Time(0),
00740         ros::Duration(3.0)));
00741     EXPECT_TRUE(tf_listener.waitForTransform(DEFAULT_IR2_OPTICAL_FRAME_ID, DEFAULT_IR2_FRAME_ID, ros::Time(0),
00742         ros::Duration(3.0)));
00743   }
00744   if (g_camera_type == "ZR300")
00745   {
00746     EXPECT_TRUE(tf_listener.waitForTransform(DEFAULT_FISHEYE_FRAME_ID, DEFAULT_BASE_FRAME_ID, ros::Time(0),
00747         ros::Duration(3.0)));
00748     EXPECT_TRUE(tf_listener.waitForTransform(DEFAULT_FISHEYE_OPTICAL_FRAME_ID, DEFAULT_FISHEYE_FRAME_ID, ros::Time(0),
00749         ros::Duration(3.0)));
00750     EXPECT_TRUE(tf_listener.waitForTransform(DEFAULT_IMU_FRAME_ID, DEFAULT_BASE_FRAME_ID, ros::Time(0),
00751         ros::Duration(3.0)));
00752     EXPECT_TRUE(tf_listener.waitForTransform(DEFAULT_IMU_OPTICAL_FRAME_ID, DEFAULT_IMU_FRAME_ID, ros::Time(0),
00753         ros::Duration(3.0)));
00754   }
00755 }
00756 
00757 TEST(RealsenseTests, testCameraOptions)
00758 {
00759   g_settings_srv_client.call(g_setting_srv);
00760   stringstream settings_ss(g_setting_srv.response.configuration_str);
00761   string setting;
00762   string setting_name;
00763   string setting_value;
00764 
00765   while (getline (settings_ss, setting, ';'))
00766   {
00767     stringstream setting_ss(setting);
00768     getline(setting_ss, setting_name, ':');
00769     setting_value = (setting.substr(setting.rfind(":") + 1));
00770     if (g_config_args.find(setting_name) != g_config_args.end())
00771     {
00772       int option_recv = atoi(setting_value.c_str());
00773       int option_exp = atoi(g_config_args.at(setting_name).c_str());
00774       EXPECT_EQ(option_exp, option_recv) << setting_name;
00775     }
00776   }
00777 }
00778 
00779 TEST(RealsenseTests, testGetSettingsService)
00780 {
00781   // Verify the service is available
00782   EXPECT_TRUE(g_settings_srv_client.call(g_setting_srv));
00783 }
00784 
00785 TEST(RealsenseTests, testSetPowerOffService)
00786 {
00787   g_setpower_srv.request.power_on = false;
00788 
00789   EXPECT_FALSE(g_setpower_srv_client.call(g_setpower_srv));
00790   ros::Duration(5).sleep();
00791 
00792   EXPECT_FALSE(g_setpower_srv.response.success);
00793 }
00794 
00795 TEST(RealsenseTests, testSetPowerOnService)
00796 {
00797   g_setpower_srv.request.power_on = true;
00798 
00799   EXPECT_TRUE(g_setpower_srv_client.call(g_setpower_srv));
00800   ros::Duration(5).sleep();
00801 
00802   EXPECT_TRUE(g_setpower_srv.response.success);
00803 }
00804 
00805 TEST(RealsenseTests, testForcePowerOffService)
00806 {
00807   g_forcepower_srv.request.power_on = false;
00808 
00809   EXPECT_TRUE(g_forcepower_srv_client.call(g_forcepower_srv));
00810   ros::Duration(5).sleep();
00811 }
00812 
00813 TEST(RealsenseTests, testIsPoweredService)
00814 {
00815   EXPECT_TRUE(g_ispowered_srv_client.call(g_ispowered_srv));
00816   EXPECT_FALSE(g_ispowered_srv.response.is_powered);
00817 }
00818 
00819 
00820 TEST(RealsenseTests, testForcePowerOnService)
00821 {
00822   g_forcepower_srv.request.power_on = true;
00823 
00824   EXPECT_TRUE(g_forcepower_srv_client.call(g_forcepower_srv));
00825   ros::Duration(5).sleep();
00826 }
00827 
00828 void fillConfigMap(int argc, char **argv)
00829 {
00830   std::vector<std::string> args;
00831 
00832   for (int i = 1; i < argc; ++i)
00833   {
00834     args.push_back(argv[i]);
00835   }
00836   while (args.size() > 1)
00837   {
00838     g_config_args[args[0]] = args[1];
00839 
00840     args.erase(args.begin());
00841     args.erase(args.begin());
00842   }
00843 
00844   if (argc > 1)
00845   {
00846     if (g_config_args.find("camera_type") != g_config_args.end())
00847     {
00848       ROS_INFO("RealSense Camera - Setting %s to %s", "camera_type", g_config_args.at("camera_type").c_str());
00849       g_camera_type = g_config_args.at("camera_type").c_str();
00850     }
00851 
00852     // Set depth arguments.
00853     if (g_config_args.find("enable_depth") != g_config_args.end())
00854     {
00855       ROS_INFO("RealSense Camera - Setting %s to %s", "enable_depth", g_config_args.at("enable_depth").c_str());
00856       if (strcmp((g_config_args.at("enable_depth").c_str ()), "true") == 0)
00857       {
00858         g_enable_depth = true;
00859       }
00860       else
00861       {
00862         g_enable_depth = false;
00863       }
00864     }
00865 
00866     // Set infrared arguments.
00867     if (g_config_args.find("enable_ir") != g_config_args.end())
00868     {
00869       ROS_INFO("RealSense Camera - Setting %s to %s", "enable_ir", g_config_args.at("enable_ir").c_str());
00870       if (strcmp((g_config_args.at("enable_ir").c_str ()), "true") == 0)
00871       {
00872         g_enable_ir = true;
00873       }
00874       else
00875       {
00876         g_enable_ir = false;
00877       }
00878     }
00879 
00880     // Set infrared2 arguments.
00881     if (g_config_args.find("enable_ir2") != g_config_args.end())
00882     {
00883       ROS_INFO("RealSense Camera - Setting %s to %s", "enable_ir2", g_config_args.at("enable_ir2").c_str());
00884       if (strcmp((g_config_args.at("enable_ir2").c_str ()), "true") == 0)
00885       {
00886         g_enable_ir2 = true;
00887       }
00888       else
00889       {
00890         g_enable_ir2 = false;
00891       }
00892     }
00893 
00894     if (g_config_args.find("depth_encoding") != g_config_args.end())
00895     {
00896       ROS_INFO("RealSense Camera - Setting %s to %s", "depth_encoding", g_config_args.at("depth_encoding").c_str());
00897       g_depth_encoding_exp = g_config_args.at("depth_encoding").c_str();
00898     }
00899     if (g_config_args.find("depth_height") != g_config_args.end())
00900     {
00901       ROS_INFO("RealSense Camera - Setting %s to %s", "depth_height", g_config_args.at("depth_height").c_str());
00902       g_depth_height_exp = atoi(g_config_args.at("depth_height").c_str());
00903     }
00904     if (g_config_args.find("depth_width") != g_config_args.end())
00905     {
00906       ROS_INFO("RealSense Camera - Setting %s to %s", "depth_width", g_config_args.at("depth_width").c_str());
00907       g_depth_width_exp = atoi(g_config_args.at("depth_width").c_str());
00908     }
00909     if (g_config_args.find("depth_step") != g_config_args.end())
00910     {
00911       ROS_INFO("RealSense Camera - Setting %s to %s", "depth_step", g_config_args.at("depth_step").c_str());
00912       g_depth_step_exp = atoi(g_config_args.at("depth_step").c_str());
00913     }
00914 
00915     // Set color arguments.
00916     if (g_config_args.find("enable_color") != g_config_args.end())
00917     {
00918       ROS_INFO("RealSense Camera - Setting %s to %s", "enable_color", g_config_args.at("enable_color").c_str());
00919       if (strcmp((g_config_args.at("enable_color").c_str ()), "true") == 0)
00920       {
00921         g_enable_color = true;
00922       }
00923       else
00924       {
00925         g_enable_color = false;
00926       }
00927     }
00928     if (g_config_args.find("color_encoding") != g_config_args.end())
00929     {
00930       ROS_INFO("RealSense Camera - Setting %s to %s", "color_encoding", g_config_args.at("color_encoding").c_str());
00931       g_color_encoding_exp = g_config_args.at("color_encoding").c_str();
00932     }
00933     if (g_config_args.find("color_height") != g_config_args.end())
00934     {
00935       ROS_INFO("RealSense Camera - Setting %s to %s", "color_height", g_config_args.at("color_height").c_str());
00936       g_color_height_exp = atoi(g_config_args.at("color_height").c_str());
00937     }
00938     if (g_config_args.find("color_width") != g_config_args.end())
00939     {
00940       ROS_INFO("RealSense Camera - Setting %s to %s", "color_width", g_config_args.at("color_width").c_str());
00941       g_color_width_exp = atoi(g_config_args.at("color_width").c_str());
00942     }
00943     if (g_config_args.find("color_step") != g_config_args.end())
00944     {
00945       ROS_INFO("RealSense Camera - Setting %s to %s", "color_step", g_config_args.at("color_step").c_str());
00946       g_color_step_exp = atoi(g_config_args.at("color_step").c_str());
00947     }
00948 
00949     // Set fisheye arguments.
00950     if (g_config_args.find("enable_fisheye") != g_config_args.end())
00951     {
00952       ROS_INFO("RealSense Camera - Setting %s to %s", "enable_fisheye",
00953           g_config_args.at("enable_fisheye").c_str());
00954       if (strcmp((g_config_args.at("enable_fisheye").c_str()), "true") == 0)
00955       {
00956         g_enable_fisheye = true;
00957       }
00958       else
00959       {
00960         g_enable_fisheye = false;
00961       }
00962     }
00963 
00964     // Set imu arguments.
00965     if (g_config_args.find("enable_imu") != g_config_args.end())
00966     {
00967       ROS_INFO("RealSense Camera - Setting %s to %s", "enable_imu",
00968           g_config_args.at("enable_imu").c_str());
00969       if (strcmp((g_config_args.at("enable_imu").c_str()), "true") == 0)
00970       {
00971         g_enable_imu = true;
00972       }
00973       else
00974       {
00975         g_enable_imu = false;
00976       }
00977     }
00978 
00979     // Set pointcloud arguments.
00980     if (g_config_args.find("enable_pointcloud") != g_config_args.end())
00981     {
00982       ROS_INFO("RealSense Camera - Setting %s to %s", "enable_pointcloud",
00983           g_config_args.at("enable_pointcloud").c_str());
00984       if (strcmp((g_config_args.at("enable_pointcloud").c_str()), "true") == 0)
00985       {
00986         g_enable_pointcloud = true;
00987       }
00988       else
00989       {
00990         g_enable_pointcloud = false;
00991       }
00992     }
00993   }
00994 }
00995 
00996 int main(int argc, char **argv) try
00997 {
00998   testing::InitGoogleTest(&argc, argv);
00999   ros::init(argc, argv, "utest");
01000   fillConfigMap(argc, argv);
01001 
01002   ROS_INFO_STREAM("RealSense Camera - Starting Tests...");
01003 
01004   ros::NodeHandle nh_base;
01005   ros::NodeHandle nh(nh_base, "camera");
01006   ros::NodeHandle depth_nh(nh, DEPTH_NAMESPACE);
01007   image_transport::ImageTransport depth_image_transport(depth_nh);
01008   g_camera_subscriber[0] = depth_image_transport.subscribeCamera(DEPTH_TOPIC, 1, imageDepthCallback, 0);
01009 
01010   ros::NodeHandle color_nh(nh, COLOR_NAMESPACE);
01011   image_transport::ImageTransport color_image_transport(color_nh);
01012   g_camera_subscriber[1] = color_image_transport.subscribeCamera(COLOR_TOPIC, 1, imageColorCallback, 0);
01013 
01014   ros::NodeHandle ir_nh(nh, IR_NAMESPACE);
01015   image_transport::ImageTransport ir_image_transport(ir_nh);
01016   g_camera_subscriber[2] = ir_image_transport.subscribeCamera(IR_TOPIC, 1, imageInfrared1Callback, 0);
01017 
01018   // R200 and ZR300 cameras have IR2
01019   if ((g_camera_type == "R200") || (g_camera_type == "ZR300"))
01020   {
01021     ros::NodeHandle ir2_nh(nh, IR2_NAMESPACE);
01022     image_transport::ImageTransport ir2_image_transport(ir2_nh);
01023     g_camera_subscriber[3] = ir2_image_transport.subscribeCamera(IR2_TOPIC, 1, imageInfrared2Callback, 0);
01024   }
01025 
01026   // ZR300 cameras have Fisheye and IMU
01027   if (g_camera_type == "ZR300")
01028   {
01029     ros::NodeHandle fisheye_nh(nh, FISHEYE_NAMESPACE);
01030     image_transport::ImageTransport fisheye_image_transport(fisheye_nh);
01031     g_camera_subscriber[4] = fisheye_image_transport.subscribeCamera(FISHEYE_TOPIC, 1, imageFisheyeCallback, 0);
01032 
01033     ros::NodeHandle imu_nh(nh, IMU_NAMESPACE);
01034     g_sub_imu = imu_nh.subscribe<sensor_msgs::Imu>(IMU_TOPIC, 1, imuCallback);
01035   }
01036 
01037   g_sub_pc = depth_nh.subscribe <sensor_msgs::PointCloud2> (PC_TOPIC, 1, pcCallback);
01038   g_settings_srv_client =
01039     nh.serviceClient<realsense_camera::CameraConfiguration>("/camera/driver/" + SETTINGS_SERVICE);
01040   g_ispowered_srv_client =
01041     nh.serviceClient<realsense_camera::IsPowered>("/camera/driver/" + CAMERA_IS_POWERED_SERVICE);
01042   g_setpower_srv_client =
01043     nh.serviceClient<realsense_camera::SetPower>("/camera/driver/" + CAMERA_SET_POWER_SERVICE);
01044   g_forcepower_srv_client =
01045     nh.serviceClient<realsense_camera::ForcePower>("/camera/driver/" + CAMERA_FORCE_POWER_SERVICE);
01046 
01047   ros::Duration duration;
01048   duration.sec = 10;
01049   duration.sleep();
01050   ros::spinOnce();
01051 
01052   return RUN_ALL_TESTS();
01053 }
01054 catch(...) {}  // catch the "testing::internal::<unnamed>::ClassUniqueToAlwaysTrue" from gtest


realsense_camera
Author(s): Rajvi Jingar , Reagan Lopez , Matt Hansen , Mark Horn
autogenerated on Thu Jun 6 2019 21:15:58