constants.h
Go to the documentation of this file.
00001 /******************************************************************************
00002  Copyright (c) 2017, 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 #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     // Default Constants.
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     // R200 and ZR300 Constants.
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     // R200 Constants.
00096     // Indoor Range: 0.7m - 3.5m, Outdoor Range: 10m
00097     const float R200_MAX_Z = 10.0f;   // in meters
00098     const std::string R200_CAMERA_FW_VERSION = "1.0.72.06";
00099     // LR200 Constants.
00100     const std::string LR200_CAMERA_FW_VERSION = "2.0.71.18";
00101     // F200 Constants.
00102     // Indoor Range: 0.2m – 1.0m, Outdoor Range: n/a
00103     const float F200_MAX_Z = 1.0f;    // in meters
00104     const std::string F200_CAMERA_FW_VERSION = "2.60.0.0";
00105 
00106     // SR300 Constants.
00107     // Indoor Range: 0.2m – 1.5m, Outdoor Range: n/a
00108     const float SR300_MAX_Z = 1.5f;   // in meters
00109     const std::string SR300_CAMERA_FW_VERSION = "3.10.10.0";
00110 
00111     // ZR300 Constants.
00112     // Indoor Range: 0.7m - 3.5m, Outdoor Range: 10m
00113     const float ZR300_MAX_Z = 10.0f;  // in meters
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     // map the camera name to its validated firmware
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 }  // namespace realsense_camera
00149 #endif  // REALSENSE_CAMERA_CONSTANTS_H


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