constants.h
Go to the documentation of this file.
1 /******************************************************************************
2  Copyright (c) 2017, 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 #include <iostream>
32 #include <string>
33 #include <utility>
34 #include <map>
35 
36 #pragma once
37 #ifndef REALSENSE_CAMERA_CONSTANTS_H
38 #define REALSENSE_CAMERA_CONSTANTS_H
39 
40 namespace realsense_camera
41 {
42  // Default Constants.
43  const int STREAM_COUNT = 5;
44  const int DEPTH_WIDTH = 480;
45  const int DEPTH_HEIGHT = 360;
46  const int COLOR_WIDTH = 640;
47  const int COLOR_HEIGHT = 480;
48  const int FISHEYE_WIDTH = 640;
49  const int FISHEYE_HEIGHT = 480;
50  const int DEPTH_FPS = 60;
51  const int COLOR_FPS = 60;
52  const int FISHEYE_FPS = 60;
53  const bool ENABLE_DEPTH = true;
54  const bool ENABLE_COLOR = true;
55  const bool ENABLE_IR = false;
56  const bool ENABLE_IR2 = false;
57  const bool ENABLE_FISHEYE = true;
58  const bool ENABLE_IMU = true;
59  const bool ENABLE_PC = false;
60  const bool ENABLE_TF = true;
61  const bool ENABLE_TF_DYNAMIC = false;
62  const double TF_PUBLICATION_RATE = 1.0;
63  const std::string DEFAULT_MODE = "preset";
64  const std::string DEFAULT_BASE_FRAME_ID = "camera_link";
65  const std::string DEFAULT_DEPTH_FRAME_ID = "camera_depth_frame";
66  const std::string DEFAULT_COLOR_FRAME_ID = "camera_rgb_frame";
67  const std::string DEFAULT_IR_FRAME_ID = "camera_ir_frame";
68  const std::string DEFAULT_DEPTH_OPTICAL_FRAME_ID = "camera_depth_optical_frame";
69  const std::string DEFAULT_COLOR_OPTICAL_FRAME_ID = "camera_rgb_optical_frame";
70  const std::string DEFAULT_IR_OPTICAL_FRAME_ID = "camera_ir_optical_frame";
71  const std::string DEPTH_NAMESPACE = "depth";
72  const std::string DEPTH_TOPIC = "image_raw";
73  const std::string PC_TOPIC = "points";
74  const std::string COLOR_NAMESPACE = "color";
75  const std::string COLOR_TOPIC = "image_raw";
76  const std::string IR_NAMESPACE = "ir";
77  const std::string IR_TOPIC = "image_raw";
78  const std::string SETTINGS_SERVICE = "get_settings";
79  const std::string CAMERA_IS_POWERED_SERVICE = "is_powered";
80  const std::string CAMERA_SET_POWER_SERVICE = "set_power";
81  const std::string CAMERA_FORCE_POWER_SERVICE = "force_power";
82  const std::string STREAM_DESC[STREAM_COUNT] = {"Depth", "Color", "IR", "IR2", "Fisheye"};
83  const int EVENT_COUNT = 2;
84  const double ROTATION_IDENTITY[] = {1, 0, 0, 0, 1, 0, 0, 0, 1};
85  const float MILLIMETER_METERS = 0.001;
86 
87  // R200 and ZR300 Constants.
88  const std::string IR2_NAMESPACE = "ir2";
89  const std::string IR2_TOPIC = "image_raw";
90  const std::string DEFAULT_IR2_FRAME_ID = "camera_ir2_frame";
91  const std::string DEFAULT_IR2_OPTICAL_FRAME_ID = "camera_ir2_optical_frame";
92 
93 
94 
95  // R200 Constants.
96  // Indoor Range: 0.7m - 3.5m, Outdoor Range: 10m
97  const float R200_MAX_Z = 10.0f; // in meters
98  const std::string R200_CAMERA_FW_VERSION = "1.0.72.06";
99  // LR200 Constants.
100  const std::string LR200_CAMERA_FW_VERSION = "2.0.71.18";
101  // F200 Constants.
102  // Indoor Range: 0.2m – 1.0m, Outdoor Range: n/a
103  const float F200_MAX_Z = 1.0f; // in meters
104  const std::string F200_CAMERA_FW_VERSION = "2.60.0.0";
105 
106  // SR300 Constants.
107  // Indoor Range: 0.2m – 1.5m, Outdoor Range: n/a
108  const float SR300_MAX_Z = 1.5f; // in meters
109  const std::string SR300_CAMERA_FW_VERSION = "3.10.10.0";
110 
111  // ZR300 Constants.
112  // Indoor Range: 0.7m - 3.5m, Outdoor Range: 10m
113  const float ZR300_MAX_Z = 10.0f; // in meters
114  const std::string FISHEYE_NAMESPACE = "fisheye";
115  const std::string FISHEYE_TOPIC = "image_raw";
116  const std::string IMU_NAMESPACE = "imu";
117  const std::string IMU_TOPIC = "data_raw";
118  const std::string IMU_INFO_SERVICE = "get_imu_info";
119  const std::string DEFAULT_FISHEYE_FRAME_ID = "camera_fisheye_frame";
120  const std::string DEFAULT_IMU_FRAME_ID = "camera_imu_frame";
121  const std::string DEFAULT_FISHEYE_OPTICAL_FRAME_ID = "camera_fisheye_optical_frame";
122  const std::string DEFAULT_IMU_OPTICAL_FRAME_ID = "camera_imu_optical_frame";
123  const std::string IMU_ACCEL = "IMU_ACCEL";
124  const std::string IMU_GYRO = "IMU_GYRO";
125  const double IMU_UNITS_TO_MSEC = 0.00003125;
126  const std::string ZR300_CAMERA_FW_VERSION = "2.0.71.28";
127  const std::string ZR300_ADAPTER_FW_VERSION = "1.29.0.0";
128  const std::string ZR300_MOTION_MODULE_FW_VERSION = "1.25.0.0";
129 
130  // map the camera name to its validated firmware
131  typedef std::pair<std::string, std::string> stringpair;
132  const stringpair MAP_START_VALUES[] =
133  {
134  stringpair("Intel RealSense R200_camera", R200_CAMERA_FW_VERSION),
135  stringpair("Intel RealSense F200_camera", F200_CAMERA_FW_VERSION),
136  stringpair("Intel RealSense SR300_camera", SR300_CAMERA_FW_VERSION),
137  stringpair("Intel RealSense ZR300_camera", ZR300_CAMERA_FW_VERSION),
138  stringpair("Intel RealSense ZR300_adapter", ZR300_ADAPTER_FW_VERSION),
139  stringpair("Intel RealSense ZR300_motion_module", ZR300_MOTION_MODULE_FW_VERSION),
140  stringpair("Intel RealSense LR200_camera", LR200_CAMERA_FW_VERSION)
141  };
142 
144  sizeof(MAP_START_VALUES[0]);
145 
146  extern const std::map<std::string, std::string> CAMERA_NAME_TO_VALIDATED_FIRMWARE;
147 
148 } // namespace realsense_camera
149 #endif // REALSENSE_CAMERA_CONSTANTS_H
const std::string PC_TOPIC
Definition: constants.h:73
const std::string DEFAULT_IR_FRAME_ID
Definition: constants.h:67
const bool ENABLE_IR
Definition: constants.h:55
const float R200_MAX_Z
Definition: constants.h:97
const int FISHEYE_WIDTH
Definition: constants.h:48
const std::string DEFAULT_DEPTH_FRAME_ID
Definition: constants.h:65
const std::string F200_CAMERA_FW_VERSION
Definition: constants.h:104
const double IMU_UNITS_TO_MSEC
Definition: constants.h:125
const bool ENABLE_COLOR
Definition: constants.h:54
const bool ENABLE_TF_DYNAMIC
Definition: constants.h:61
const std::string COLOR_NAMESPACE
Definition: constants.h:74
const std::string FISHEYE_NAMESPACE
Definition: constants.h:114
const float MILLIMETER_METERS
Definition: constants.h:85
const std::string IMU_NAMESPACE
Definition: constants.h:116
const std::string DEFAULT_COLOR_FRAME_ID
Definition: constants.h:66
const std::string DEFAULT_FISHEYE_FRAME_ID
Definition: constants.h:119
const float SR300_MAX_Z
Definition: constants.h:108
const bool ENABLE_DEPTH
Definition: constants.h:53
const std::string STREAM_DESC[STREAM_COUNT]
Definition: constants.h:82
const int DEPTH_HEIGHT
Definition: constants.h:45
const std::string CAMERA_IS_POWERED_SERVICE
Definition: constants.h:79
const float ZR300_MAX_Z
Definition: constants.h:113
const std::string DEFAULT_IR_OPTICAL_FRAME_ID
Definition: constants.h:70
const float F200_MAX_Z
Definition: constants.h:103
const int COLOR_HEIGHT
Definition: constants.h:47
const int MAP_START_VALUES_SIZE
Definition: constants.h:143
const std::string LR200_CAMERA_FW_VERSION
Definition: constants.h:100
const std::string IMU_INFO_SERVICE
Definition: constants.h:118
const bool ENABLE_FISHEYE
Definition: constants.h:57
const std::string SR300_CAMERA_FW_VERSION
Definition: constants.h:109
const std::string IMU_GYRO
Definition: constants.h:124
const bool ENABLE_IR2
Definition: constants.h:56
const std::string FISHEYE_TOPIC
Definition: constants.h:115
const std::string IMU_ACCEL
Definition: constants.h:123
const std::string IR2_TOPIC
Definition: constants.h:89
const std::string DEFAULT_IMU_OPTICAL_FRAME_ID
Definition: constants.h:122
const std::string DEFAULT_COLOR_OPTICAL_FRAME_ID
Definition: constants.h:69
const std::string R200_CAMERA_FW_VERSION
Definition: constants.h:98
const std::string IR2_NAMESPACE
Definition: constants.h:88
const std::string IR_TOPIC
Definition: constants.h:77
const int DEPTH_FPS
Definition: constants.h:50
const std::string DEFAULT_IMU_FRAME_ID
Definition: constants.h:120
const std::string COLOR_TOPIC
Definition: constants.h:75
const std::string IMU_TOPIC
Definition: constants.h:117
const std::string DEFAULT_BASE_FRAME_ID
Definition: constants.h:64
const std::map< std::string, std::string > CAMERA_NAME_TO_VALIDATED_FIRMWARE
const bool ENABLE_IMU
Definition: constants.h:58
const double TF_PUBLICATION_RATE
Definition: constants.h:62
const std::string DEPTH_TOPIC
Definition: constants.h:72
const std::string ZR300_CAMERA_FW_VERSION
Definition: constants.h:126
const bool ENABLE_TF
Definition: constants.h:60
const std::string DEFAULT_DEPTH_OPTICAL_FRAME_ID
Definition: constants.h:68
const std::string DEPTH_NAMESPACE
Definition: constants.h:71
const double ROTATION_IDENTITY[]
Definition: constants.h:84
const int STREAM_COUNT
Definition: constants.h:43
const int FISHEYE_FPS
Definition: constants.h:52
const std::string DEFAULT_IR2_FRAME_ID
Definition: constants.h:90
const int COLOR_WIDTH
Definition: constants.h:46
const std::string DEFAULT_IR2_OPTICAL_FRAME_ID
Definition: constants.h:91
const std::string IR_NAMESPACE
Definition: constants.h:76
const std::string ZR300_MOTION_MODULE_FW_VERSION
Definition: constants.h:128
const int DEPTH_WIDTH
Definition: constants.h:44
const std::string CAMERA_FORCE_POWER_SERVICE
Definition: constants.h:81
std::pair< std::string, std::string > stringpair
Definition: constants.h:131
const int COLOR_FPS
Definition: constants.h:51
const int EVENT_COUNT
Definition: constants.h:83
const std::string CAMERA_SET_POWER_SERVICE
Definition: constants.h:80
const int FISHEYE_HEIGHT
Definition: constants.h:49
const std::string SETTINGS_SERVICE
Definition: constants.h:78
const bool ENABLE_PC
Definition: constants.h:59
const std::string DEFAULT_FISHEYE_OPTICAL_FRAME_ID
Definition: constants.h:121
const std::string DEFAULT_MODE
Definition: constants.h:63
const stringpair MAP_START_VALUES[]
Definition: constants.h:132
const std::string ZR300_ADAPTER_FW_VERSION
Definition: constants.h:127


realsense_camera
Author(s): Rajvi Jingar , Reagan Lopez , Matt Hansen , Mark Horn
autogenerated on Mon Jun 10 2019 14:40:37