camera_core.h
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 
31 #pragma once
32 #ifndef CAMERA_CORE_H // NOLINT(build/header_guard)
33 #define CAMERA_CORE_H
34 
35 #include <cstdlib>
36 #include <cctype>
37 #include <sstream>
38 #include <iostream>
39 #include <vector>
40 #include <map>
41 #include <string>
42 
43 #include <sensor_msgs/PointCloud2.h>
44 #include <sensor_msgs/Imu.h>
48 
50 #include <std_msgs/String.h>
51 #include <ros/ros.h>
52 #include <pcl/conversions.h>
53 #include <pcl/point_cloud.h>
54 #include <pcl/point_types.h>
55 #include <pcl/PCLPointCloud2.h>
57 #include <std_msgs/Float32MultiArray.h>
58 #include <cv_bridge/cv_bridge.h>
59 #include <realsense_camera/CameraConfiguration.h>
60 #include <realsense_camera/IsPowered.h>
61 #include <realsense_camera/SetPower.h>
62 #include <realsense_camera/ForcePower.h>
63 #include <tf/transform_listener.h>
64 #include <librealsense/rs.h>
66 
69 
70 // utest commandline args
75 uint32_t g_depth_step_exp; // Expected depth step.
76 uint32_t g_color_step_exp; // Expected color step.
77 uint32_t g_infrared1_step_exp; // Expected infrared1 step.
78 
79 bool g_enable_color = true;
80 bool g_enable_depth = true;
81 bool g_enable_fisheye = false;
82 bool g_enable_imu = false;
83 bool g_enable_pointcloud = false;
84 bool g_enable_ir = false;
85 bool g_enable_ir2 = false;
86 
87 std::string g_depth_encoding_exp; // Expected depth encoding.
88 std::string g_color_encoding_exp; // Expected color encoding.
89 std::string g_infrared1_encoding_exp; // Expected infrared1 encoding.
90 
94 
99 
100 std::map<std::string, std::string> g_config_args;
101 double g_max_z = R200_MAX_Z * 1000.0f; // Converting meter to mm.
102 
103 bool g_depth_recv = false;
104 bool g_color_recv = false;
105 bool g_infrared1_recv = false;
106 bool g_infrared2_recv = false;
107 bool g_fisheye_recv = false;
108 bool g_imu_recv = false;
109 bool g_pc_recv = false;
110 
111 float g_depth_avg = 0.0f;
112 float g_color_avg = 0.0f;
113 float g_infrared1_avg = 0.0f;
114 float g_infrared2_avg = 0.0f;
115 float g_fisheye_avg = 0.0f;
116 float g_pc_depth_avg = 0.0f;
117 
120 uint32_t g_step_recv[STREAM_COUNT] = {0}; // Received stream step.
121 
122 std::string g_encoding_recv[STREAM_COUNT]; // Expected stream encoding.
123 
126 double g_color_caminfo_D_recv[5] = {0.0};
127 double g_depth_caminfo_D_recv[5] = {0.0};
128 double g_infrared1_caminfo_D_recv[5] = {0.0};
129 double g_infrared2_caminfo_D_recv[5] = {0.0};
130 double g_fisheye_caminfo_D_recv[5] = {0.0};
131 
134 
136 std::string g_camera_type;
137 
138 realsense_camera::CameraConfiguration g_setting_srv;
139 realsense_camera::IsPowered g_ispowered_srv;
140 realsense_camera::SetPower g_setpower_srv;
141 realsense_camera::ForcePower g_forcepower_srv;
142 
143 #endif // CAMERA_CORE_H // NOLINT(build/header_guard)
bool g_pc_recv
Definition: camera_core.h:109
std::string g_depth_encoding_exp
Definition: camera_core.h:87
float g_pc_depth_avg
Definition: camera_core.h:116
ros::ServiceClient g_ispowered_srv_client
Definition: camera_core.h:96
const float R200_MAX_Z
Definition: constants.h:97
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
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
uint32_t g_depth_step_exp
Definition: camera_core.h:75
double g_caminfo_projection_recv[STREAM_COUNT][12]
Definition: camera_core.h:133
realsense_camera::SetPower g_setpower_srv
Definition: camera_core.h:140
ros::Subscriber g_sub_pc
Definition: camera_core.h:93
int g_caminfo_height_recv[STREAM_COUNT]
Definition: camera_core.h:124
std::string g_encoding_recv[STREAM_COUNT]
Definition: camera_core.h:122
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
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
double g_max_z
Definition: camera_core.h:101
uint32_t g_infrared1_step_exp
Definition: camera_core.h:77
bool g_infrared1_recv
Definition: camera_core.h:105
ros::ServiceClient g_forcepower_srv_client
Definition: camera_core.h:98
double g_fisheye_caminfo_D_recv[5]
Definition: camera_core.h:130
float g_fisheye_avg
Definition: camera_core.h:115
std::string g_color_encoding_exp
Definition: camera_core.h:88
bool g_enable_color
Definition: camera_core.h:79
bool g_imu_recv
Definition: camera_core.h:108
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
int g_depth_height_exp
Definition: camera_core.h:73
float g_infrared2_avg
Definition: camera_core.h:114
int g_height_recv[STREAM_COUNT]
Definition: camera_core.h:118
const int STREAM_COUNT
Definition: constants.h:43
bool g_fisheye_recv
Definition: camera_core.h:107
bool g_color_recv
Definition: camera_core.h:104
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
std::string g_dmodel_recv[STREAM_COUNT]
Definition: camera_core.h:135
std::string g_infrared1_encoding_exp
Definition: camera_core.h:89
double g_infrared1_caminfo_D_recv[5]
Definition: camera_core.h:128
double g_infrared2_caminfo_D_recv[5]
Definition: camera_core.h:129
bool g_enable_depth
Definition: camera_core.h:80
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