rgbd_topics.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 
00031 #include "rgbd_topics.h"  // NOLINT(build/include)
00032 
00033 void topic0Callback(const sensor_msgs::ImageConstPtr msg)
00034 {
00035   if ((msg->height != 0) && (msg->width != 0))
00036   {
00037     topic_0_recv = true;
00038   }
00039 }
00040 
00041 void topic1Callback(const sensor_msgs::ImageConstPtr msg)
00042 {
00043   if ((msg->height != 0) && (msg->width != 0))
00044   {
00045     topic_1_recv = true;
00046   }
00047 }
00048 
00049 void topic2Callback(const sensor_msgs::ImageConstPtr msg)
00050 {
00051   if ((msg->height != 0) && (msg->width != 0))
00052   {
00053     topic_2_recv = true;
00054   }
00055 }
00056 
00057 void topic3Callback(const sensor_msgs::ImageConstPtr msg)
00058 {
00059   if ((msg->height != 0) && (msg->width != 0))
00060   {
00061     topic_3_recv = true;
00062   }
00063 }
00064 
00065 void topic4Callback(const sensor_msgs::ImageConstPtr msg)
00066 {
00067   if ((msg->height != 0) && (msg->width != 0))
00068   {
00069     topic_4_recv = true;
00070   }
00071 }
00072 
00073 void topic5Callback(const sensor_msgs::ImageConstPtr msg)
00074 {
00075   if ((msg->height != 0) && (msg->width != 0))
00076   {
00077     topic_5_recv = true;
00078   }
00079 }
00080 
00081 void topic6Callback(const sensor_msgs::ImageConstPtr msg)
00082 {
00083   if ((msg->height != 0) && (msg->width != 0))
00084   {
00085     topic_6_recv = true;
00086   }
00087 }
00088 
00089 void topic7Callback(const sensor_msgs::PointCloud2ConstPtr msg)
00090 {
00091   if ((msg->height != 0) && (msg->width != 0))
00092   {
00093     topic_7_recv = true;
00094   }
00095 }
00096 
00097 void topic8Callback(const sensor_msgs::ImageConstPtr msg)
00098 {
00099   if ((msg->height != 0) && (msg->width != 0))
00100   {
00101     topic_8_recv = true;
00102   }
00103 }
00104 
00105 void topic9Callback(const sensor_msgs::ImageConstPtr msg)
00106 {
00107   if ((msg->height != 0) && (msg->width != 0))
00108   {
00109     topic_9_recv = true;
00110   }
00111 }
00112 
00113 void topic10Callback(const sensor_msgs::CameraInfoConstPtr msg)
00114 {
00115   if ((msg->height != 0) && (msg->width != 0))
00116   {
00117     topic_10_recv = true;
00118   }
00119 }
00120 
00121 void topic11Callback(const sensor_msgs::PointCloud2ConstPtr msg)
00122 {
00123   if ((msg->height != 0) && (msg->width != 0))
00124   {
00125     topic_11_recv = true;
00126   }
00127 }
00128 
00129 void topic12Callback(const sensor_msgs::ImageConstPtr msg)
00130 {
00131   if ((msg->height != 0) && (msg->width != 0))
00132   {
00133     topic_12_recv = true;
00134   }
00135 }
00136 
00137 TEST(RealsenseTests, rgb_image_mono)
00138 {
00139   EXPECT_TRUE(topic_0_recv);
00140 }
00141 
00142 TEST(RealsenseTests, rgb_image_color)
00143 {
00144   EXPECT_TRUE(topic_1_recv);
00145 }
00146 
00147 TEST(RealsenseTests, rgb_image_rect_mono)
00148 {
00149   EXPECT_TRUE(topic_2_recv);
00150 }
00151 
00152 TEST(RealsenseTests, rgb_image_rect_color)
00153 {
00154   EXPECT_TRUE(topic_3_recv);
00155 }
00156 
00157 TEST(RealsenseTests, depth_image_rect_raw)
00158 {
00159   EXPECT_TRUE(topic_4_recv);
00160 }
00161 
00162 TEST(RealsenseTests, depth_image_rect)
00163 {
00164   EXPECT_TRUE(topic_5_recv);
00165 }
00166 
00167 TEST(RealsenseTests, depth_image)
00168 {
00169   EXPECT_TRUE(topic_6_recv);
00170 }
00171 
00172 TEST(RealsenseTests, depth_points)
00173 {
00174   EXPECT_TRUE(topic_7_recv);
00175 }
00176 
00177 TEST(RealsenseTests, ir_image_rect_ir)
00178 {
00179   EXPECT_TRUE(topic_8_recv);
00180 }
00181 
00182 TEST(RealsenseTests, depth_reg_sw_reg_image_rect_raw)
00183 {
00184   EXPECT_TRUE(topic_9_recv);
00185 }
00186 
00187 TEST(RealsenseTests, depth_reg_sw_reg_camera_info)
00188 {
00189   EXPECT_TRUE(topic_10_recv);
00190 }
00191 
00192 TEST(RealsenseTests, depth_reg_points)
00193 {
00194   EXPECT_TRUE(topic_11_recv);
00195 }
00196 
00197 TEST(RealsenseTests, depth_reg_sw_reg_image_rect)
00198 {
00199   EXPECT_TRUE(topic_12_recv);
00200 }
00201 
00202 void getParams()
00203 {
00204   ros::NodeHandle pnh;
00205   pnh.param("camera", camera, CAMERA);
00206   pnh.param("rgb", rgb, RGB);
00207   pnh.param("depth", depth, DEPTH);
00208   pnh.param("ir", ir, IR);
00209   pnh.param("depth_registered", depth_registered, DEPTH_REGISTERED);
00210 }
00211 
00212 void setTopics()
00213 {
00214   rgb_image_mono = "/" + camera + "/" + rgb + "/" + RGB_IMAGE_MONO;
00215   rgb_image_color = "/" + camera + "/" + rgb + "/" + RGB_IMAGE_COLOR;
00216   rgb_image_rect_mono = "/" + camera + "/" + rgb + "/" + RGB_IMAGE_RECT_MONO;
00217   rgb_image_rect_color = "/" + camera + "/" + rgb + "/" + RGB_IMAGE_RECT_COLOR;
00218   depth_image_rect_raw = "/" + camera + "/" + depth + "/" + DEPTH_IMAGE_RECT_RAW;
00219   depth_image_rect = "/" + camera + "/" + depth + "/" + DEPTH_IMAGE_RECT;
00220   depth_image = "/" + camera + "/" + depth + "/" + DEPTH_IMAGE;
00221   depth_points = "/" + camera + "/" + depth + "/" + DEPTH_POINTS;
00222   ir_image_rect_ir = "/" + camera + "/" + ir + "/" + IR_IMAGE_RECT_IR;
00223   depth_reg_sw_reg_image_rect_raw = "/" + camera + "/" + depth_registered + "/" + DEPTH_REG_SW_REG_IMAGE_RECT_RAW;
00224   depth_reg_sw_reg_camera_info = "/" + camera + "/" + depth_registered + "/" + DEPTH_REG_SW_REG_CAMERA_INFO;
00225   depth_reg_points = "/" + camera + "/" + depth_registered + "/" + DEPTH_REG_POINTS;
00226   depth_reg_sw_reg_image_rect = "/" + camera + "/" + depth_registered + "/" + DEPTH_REG_SW_REG_IMAGE_RECT;
00227 }
00228 
00229 int main(int argc, char **argv) try
00230 {
00231   testing::InitGoogleTest(&argc, argv);
00232   ros::init(argc, argv, "utest");
00233 
00234   ROS_INFO_STREAM("RealSense Camera - Starting rgbd_launch Tests...");
00235 
00236   ros::NodeHandle nh;
00237   getParams();
00238   setTopics();
00239 
00240   subscriber[0] = nh.subscribe<sensor_msgs::Image>(rgb_image_mono, 1, topic0Callback, 0);
00241   subscriber[1] = nh.subscribe<sensor_msgs::Image>(rgb_image_color, 1, topic1Callback, 0);
00242   subscriber[2] = nh.subscribe<sensor_msgs::Image>(rgb_image_rect_mono, 1, topic2Callback, 0);
00243   subscriber[3] = nh.subscribe<sensor_msgs::Image>(rgb_image_rect_color, 1, topic3Callback, 0);
00244   subscriber[4] = nh.subscribe<sensor_msgs::Image>(depth_image_rect_raw, 1, topic4Callback, 0);
00245   subscriber[5] = nh.subscribe<sensor_msgs::Image>(depth_image_rect, 1, topic5Callback, 0);
00246   subscriber[6] = nh.subscribe<sensor_msgs::Image>(depth_image, 1, topic6Callback, 0);
00247   subscriber[7] = nh.subscribe<sensor_msgs::PointCloud2>(depth_points, 1, topic7Callback);
00248   subscriber[8] = nh.subscribe<sensor_msgs::Image>(ir_image_rect_ir, 1, topic8Callback, 0);
00249   subscriber[9] = nh.subscribe<sensor_msgs::Image>(depth_reg_sw_reg_image_rect_raw, 1, topic9Callback, 0);
00250   subscriber[10] = nh.subscribe<sensor_msgs::CameraInfo>(depth_reg_sw_reg_camera_info, 1, topic10Callback);
00251   subscriber[11] = nh.subscribe<sensor_msgs::PointCloud2>(depth_reg_points, 1, topic11Callback, 0);
00252   subscriber[12] = nh.subscribe<sensor_msgs::Image>(depth_reg_sw_reg_image_rect, 1, topic12Callback, 0);
00253 
00254   ros::Duration duration;
00255   duration.sec = 10;
00256   duration.sleep();
00257   ros::spinOnce();
00258 
00259   return RUN_ALL_TESTS();
00260 }
00261 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