camera_core.h
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 #pragma once
00032 #ifndef CAMERA_CORE_H  // NOLINT(build/header_guard)
00033 #define CAMERA_CORE_H
00034 
00035 #include <cstdlib>
00036 #include <cctype>
00037 #include <sstream>
00038 #include <iostream>
00039 #include <vector>
00040 #include <map>
00041 #include <string>
00042 
00043 #include <sensor_msgs/PointCloud2.h>
00044 #include <sensor_msgs/Imu.h>
00045 #include <sensor_msgs/point_cloud2_iterator.h>
00046 #include <sensor_msgs/image_encodings.h>
00047 #include <image_transport/image_transport.h>
00048 
00049 #include <camera_info_manager/camera_info_manager.h>
00050 #include <std_msgs/String.h>
00051 #include <ros/ros.h>
00052 #include <pcl/conversions.h>
00053 #include <pcl/point_cloud.h>
00054 #include <pcl/point_types.h>
00055 #include <pcl/PCLPointCloud2.h>
00056 #include <pcl_conversions/pcl_conversions.h>
00057 #include <std_msgs/Float32MultiArray.h>
00058 #include <cv_bridge/cv_bridge.h>
00059 #include <realsense_camera/CameraConfiguration.h>
00060 #include <realsense_camera/IsPowered.h>
00061 #include <realsense_camera/SetPower.h>
00062 #include <realsense_camera/ForcePower.h>
00063 #include <tf/transform_listener.h>
00064 #include <librealsense/rs.h>
00065 #include <realsense_camera/constants.h>
00066 
00067 using realsense_camera::STREAM_COUNT;
00068 using realsense_camera::R200_MAX_Z;
00069 
00070 // utest commandline args
00071 int g_color_height_exp = 0;
00072 int g_color_width_exp = 0;
00073 int g_depth_height_exp = 0;
00074 int g_depth_width_exp = 0;
00075 uint32_t g_depth_step_exp;  // Expected depth step.
00076 uint32_t g_color_step_exp;  // Expected color step.
00077 uint32_t g_infrared1_step_exp;  // Expected infrared1 step.
00078 
00079 bool g_enable_color = true;
00080 bool g_enable_depth = true;
00081 bool g_enable_fisheye = false;
00082 bool g_enable_imu = false;
00083 bool g_enable_pointcloud = false;
00084 bool g_enable_ir = false;
00085 bool g_enable_ir2 = false;
00086 
00087 std::string g_depth_encoding_exp;  // Expected depth encoding.
00088 std::string g_color_encoding_exp;  // Expected color encoding.
00089 std::string g_infrared1_encoding_exp;  // Expected infrared1 encoding.
00090 
00091 image_transport::CameraSubscriber g_camera_subscriber[STREAM_COUNT];
00092 ros::Subscriber g_sub_imu;
00093 ros::Subscriber g_sub_pc;
00094 
00095 ros::ServiceClient g_settings_srv_client;
00096 ros::ServiceClient g_ispowered_srv_client;
00097 ros::ServiceClient g_setpower_srv_client;
00098 ros::ServiceClient g_forcepower_srv_client;
00099 
00100 std::map<std::string, std::string> g_config_args;
00101 double g_max_z = R200_MAX_Z * 1000.0f;  // Converting meter to mm.
00102 
00103 bool g_depth_recv = false;
00104 bool g_color_recv = false;
00105 bool g_infrared1_recv = false;
00106 bool g_infrared2_recv = false;
00107 bool g_fisheye_recv = false;
00108 bool g_imu_recv = false;
00109 bool g_pc_recv = false;
00110 
00111 float g_depth_avg = 0.0f;
00112 float g_color_avg = 0.0f;
00113 float g_infrared1_avg = 0.0f;
00114 float g_infrared2_avg = 0.0f;
00115 float g_fisheye_avg = 0.0f;
00116 float g_pc_depth_avg = 0.0f;
00117 
00118 int g_height_recv[STREAM_COUNT] = {0};
00119 int g_width_recv[STREAM_COUNT] = {0};
00120 uint32_t g_step_recv[STREAM_COUNT] = {0};  // Received stream step.
00121 
00122 std::string g_encoding_recv[STREAM_COUNT];  // Expected stream encoding.
00123 
00124 int g_caminfo_height_recv[STREAM_COUNT] = {0};
00125 int g_caminfo_width_recv[STREAM_COUNT] = {0};
00126 double g_color_caminfo_D_recv[5] = {0.0};
00127 double g_depth_caminfo_D_recv[5] = {0.0};
00128 double g_infrared1_caminfo_D_recv[5] = {0.0};
00129 double g_infrared2_caminfo_D_recv[5] = {0.0};
00130 double g_fisheye_caminfo_D_recv[5] = {0.0};
00131 
00132 double g_caminfo_rotation_recv[STREAM_COUNT][9] = {{0.0}};
00133 double g_caminfo_projection_recv[STREAM_COUNT][12] = {{0.0}};
00134 
00135 std::string g_dmodel_recv[STREAM_COUNT];
00136 std::string g_camera_type;
00137 
00138 realsense_camera::CameraConfiguration g_setting_srv;
00139 realsense_camera::IsPowered g_ispowered_srv;
00140 realsense_camera::SetPower g_setpower_srv;
00141 realsense_camera::ForcePower g_forcepower_srv;
00142 
00143 #endif  // CAMERA_CORE_H  // NOLINT(build/header_guard)


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