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 #pragma once 00032 #ifndef RGBD_TOPICS_H // NOLINT(build/header_guard) 00033 #define RGBD_TOPICS_H 00034 00035 #include <string> 00036 00037 #include <sensor_msgs/image_encodings.h> 00038 #include <camera_info_manager/camera_info_manager.h> 00039 #include <std_msgs/String.h> 00040 #include <ros/ros.h> 00041 #include <pcl_conversions/pcl_conversions.h> 00042 #include <gtest/gtest.h> 00043 00044 static const int TOPIC_COUNT = 13; 00045 00046 std::string RGB_IMAGE_MONO = "image_mono"; 00047 std::string RGB_IMAGE_COLOR = "image_color"; 00048 std::string RGB_IMAGE_RECT_MONO = "image_rect_mono"; 00049 std::string RGB_IMAGE_RECT_COLOR = "image_rect_color"; 00050 std::string DEPTH_IMAGE_RECT_RAW = "image_rect_raw"; 00051 std::string DEPTH_IMAGE_RECT = "image_rect"; 00052 std::string DEPTH_IMAGE = "image"; 00053 std::string DEPTH_POINTS = "points"; 00054 std::string IR_IMAGE_RECT_IR = "image_rect_ir"; 00055 std::string DEPTH_REG_SW_REG_IMAGE_RECT_RAW = "sw_registered/image_rect_raw"; 00056 std::string DEPTH_REG_SW_REG_CAMERA_INFO = "sw_registered/camera_info"; 00057 std::string DEPTH_REG_POINTS = "points"; 00058 std::string DEPTH_REG_SW_REG_IMAGE_RECT = "sw_registered/image_rect"; 00059 00060 std::string CAMERA = "camera"; 00061 std::string RGB = "rgb"; 00062 std::string DEPTH = "depth"; 00063 std::string IR = "ir"; 00064 std::string DEPTH_REGISTERED = "depth_registered"; 00065 00066 std::string camera; 00067 std::string rgb; 00068 std::string depth; 00069 std::string ir; 00070 std::string depth_registered; 00071 00072 std::string rgb_image_mono; 00073 std::string rgb_image_color; 00074 std::string rgb_image_rect_mono; 00075 std::string rgb_image_rect_color; 00076 std::string depth_image_rect_raw; 00077 std::string depth_image_rect; 00078 std::string depth_image; 00079 std::string depth_points; 00080 std::string ir_image_rect_ir; 00081 std::string depth_reg_sw_reg_image_rect_raw; 00082 std::string depth_reg_sw_reg_camera_info; 00083 std::string depth_reg_points; 00084 std::string depth_reg_sw_reg_image_rect; 00085 00086 bool topic_0_recv = false; 00087 bool topic_1_recv = false; 00088 bool topic_2_recv = false; 00089 bool topic_3_recv = false; 00090 bool topic_4_recv = false; 00091 bool topic_5_recv = false; 00092 bool topic_6_recv = false; 00093 bool topic_7_recv = false; 00094 bool topic_8_recv = false; 00095 bool topic_9_recv = false; 00096 bool topic_10_recv = false; 00097 bool topic_11_recv = false; 00098 bool topic_12_recv = false; 00099 00100 ros::Subscriber subscriber[TOPIC_COUNT]; 00101 #endif // RGBD_TOPICS_H // NOLINT(build/header_guard)