Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031 #include <iostream>
00032 #include <string>
00033 #include <utility>
00034 #include <map>
00035
00036 #pragma once
00037 #ifndef REALSENSE_CAMERA_CONSTANTS_H
00038 #define REALSENSE_CAMERA_CONSTANTS_H
00039
00040 namespace realsense_camera
00041 {
00042
00043 const int STREAM_COUNT = 5;
00044 const int DEPTH_WIDTH = 480;
00045 const int DEPTH_HEIGHT = 360;
00046 const int COLOR_WIDTH = 640;
00047 const int COLOR_HEIGHT = 480;
00048 const int FISHEYE_WIDTH = 640;
00049 const int FISHEYE_HEIGHT = 480;
00050 const int DEPTH_FPS = 60;
00051 const int COLOR_FPS = 60;
00052 const int FISHEYE_FPS = 60;
00053 const bool ENABLE_DEPTH = true;
00054 const bool ENABLE_COLOR = true;
00055 const bool ENABLE_IR = false;
00056 const bool ENABLE_IR2 = false;
00057 const bool ENABLE_FISHEYE = true;
00058 const bool ENABLE_IMU = true;
00059 const bool ENABLE_PC = false;
00060 const bool ENABLE_TF = true;
00061 const bool ENABLE_TF_DYNAMIC = false;
00062 const double TF_PUBLICATION_RATE = 1.0;
00063 const std::string DEFAULT_MODE = "preset";
00064 const std::string DEFAULT_BASE_FRAME_ID = "camera_link";
00065 const std::string DEFAULT_DEPTH_FRAME_ID = "camera_depth_frame";
00066 const std::string DEFAULT_COLOR_FRAME_ID = "camera_rgb_frame";
00067 const std::string DEFAULT_IR_FRAME_ID = "camera_ir_frame";
00068 const std::string DEFAULT_DEPTH_OPTICAL_FRAME_ID = "camera_depth_optical_frame";
00069 const std::string DEFAULT_COLOR_OPTICAL_FRAME_ID = "camera_rgb_optical_frame";
00070 const std::string DEFAULT_IR_OPTICAL_FRAME_ID = "camera_ir_optical_frame";
00071 const std::string DEPTH_NAMESPACE = "depth";
00072 const std::string DEPTH_TOPIC = "image_raw";
00073 const std::string PC_TOPIC = "points";
00074 const std::string COLOR_NAMESPACE = "color";
00075 const std::string COLOR_TOPIC = "image_raw";
00076 const std::string IR_NAMESPACE = "ir";
00077 const std::string IR_TOPIC = "image_raw";
00078 const std::string SETTINGS_SERVICE = "get_settings";
00079 const std::string CAMERA_IS_POWERED_SERVICE = "is_powered";
00080 const std::string CAMERA_SET_POWER_SERVICE = "set_power";
00081 const std::string CAMERA_FORCE_POWER_SERVICE = "force_power";
00082 const std::string STREAM_DESC[STREAM_COUNT] = {"Depth", "Color", "IR", "IR2", "Fisheye"};
00083 const int EVENT_COUNT = 2;
00084 const double ROTATION_IDENTITY[] = {1, 0, 0, 0, 1, 0, 0, 0, 1};
00085 const float MILLIMETER_METERS = 0.001;
00086
00087
00088 const std::string IR2_NAMESPACE = "ir2";
00089 const std::string IR2_TOPIC = "image_raw";
00090 const std::string DEFAULT_IR2_FRAME_ID = "camera_ir2_frame";
00091 const std::string DEFAULT_IR2_OPTICAL_FRAME_ID = "camera_ir2_optical_frame";
00092
00093
00094
00095
00096
00097 const float R200_MAX_Z = 10.0f;
00098 const std::string R200_CAMERA_FW_VERSION = "1.0.72.06";
00099
00100 const std::string LR200_CAMERA_FW_VERSION = "2.0.71.18";
00101
00102
00103 const float F200_MAX_Z = 1.0f;
00104 const std::string F200_CAMERA_FW_VERSION = "2.60.0.0";
00105
00106
00107
00108 const float SR300_MAX_Z = 1.5f;
00109 const std::string SR300_CAMERA_FW_VERSION = "3.10.10.0";
00110
00111
00112
00113 const float ZR300_MAX_Z = 10.0f;
00114 const std::string FISHEYE_NAMESPACE = "fisheye";
00115 const std::string FISHEYE_TOPIC = "image_raw";
00116 const std::string IMU_NAMESPACE = "imu";
00117 const std::string IMU_TOPIC = "data_raw";
00118 const std::string IMU_INFO_SERVICE = "get_imu_info";
00119 const std::string DEFAULT_FISHEYE_FRAME_ID = "camera_fisheye_frame";
00120 const std::string DEFAULT_IMU_FRAME_ID = "camera_imu_frame";
00121 const std::string DEFAULT_FISHEYE_OPTICAL_FRAME_ID = "camera_fisheye_optical_frame";
00122 const std::string DEFAULT_IMU_OPTICAL_FRAME_ID = "camera_imu_optical_frame";
00123 const std::string IMU_ACCEL = "IMU_ACCEL";
00124 const std::string IMU_GYRO = "IMU_GYRO";
00125 const double IMU_UNITS_TO_MSEC = 0.00003125;
00126 const std::string ZR300_CAMERA_FW_VERSION = "2.0.71.28";
00127 const std::string ZR300_ADAPTER_FW_VERSION = "1.29.0.0";
00128 const std::string ZR300_MOTION_MODULE_FW_VERSION = "1.25.0.0";
00129
00130
00131 typedef std::pair<std::string, std::string> stringpair;
00132 const stringpair MAP_START_VALUES[] =
00133 {
00134 stringpair("Intel RealSense R200_camera", R200_CAMERA_FW_VERSION),
00135 stringpair("Intel RealSense F200_camera", F200_CAMERA_FW_VERSION),
00136 stringpair("Intel RealSense SR300_camera", SR300_CAMERA_FW_VERSION),
00137 stringpair("Intel RealSense ZR300_camera", ZR300_CAMERA_FW_VERSION),
00138 stringpair("Intel RealSense ZR300_adapter", ZR300_ADAPTER_FW_VERSION),
00139 stringpair("Intel RealSense ZR300_motion_module", ZR300_MOTION_MODULE_FW_VERSION),
00140 stringpair("Intel RealSense LR200_camera", LR200_CAMERA_FW_VERSION)
00141 };
00142
00143 const int MAP_START_VALUES_SIZE = sizeof(MAP_START_VALUES) /
00144 sizeof(MAP_START_VALUES[0]);
00145
00146 extern const std::map<std::string, std::string> CAMERA_NAME_TO_VALIDATED_FIRMWARE;
00147
00148 }
00149 #endif // REALSENSE_CAMERA_CONSTANTS_H