constants.h
Go to the documentation of this file.
00001 // License: Apache 2.0. See LICENSE file in root directory.
00002 // Copyright(c) 2018 Intel Corporation. All Rights Reserved
00003 
00004 #pragma once
00005 
00006 #include <string>
00007 
00008 #define REALSENSE_ROS_MAJOR_VERSION    2
00009 #define REALSENSE_ROS_MINOR_VERSION    2
00010 #define REALSENSE_ROS_PATCH_VERSION    6
00011 
00012 #define STRINGIFY(arg) #arg
00013 #define VAR_ARG_STRING(arg) STRINGIFY(arg)
00014 /* Return version in "X.Y.Z" format */
00015 #define REALSENSE_ROS_VERSION_STR (VAR_ARG_STRING(REALSENSE_ROS_MAJOR_VERSION.REALSENSE_ROS_MINOR_VERSION.REALSENSE_ROS_PATCH_VERSION))
00016 
00017 namespace realsense2_camera
00018 {
00019     const uint16_t SR300_PID        = 0x0aa5; // SR300
00020     const uint16_t RS400_PID        = 0x0ad1; // PSR
00021     const uint16_t RS410_PID        = 0x0ad2; // ASR
00022     const uint16_t RS415_PID        = 0x0ad3; // ASRC
00023     const uint16_t RS430_PID        = 0x0ad4; // AWG
00024     const uint16_t RS430_MM_PID     = 0x0ad5; // AWGT
00025     const uint16_t RS_USB2_PID      = 0x0ad6; // USB2
00026     const uint16_t RS420_PID        = 0x0af6; // PWG
00027     const uint16_t RS420_MM_PID     = 0x0afe; // PWGT
00028     const uint16_t RS410_MM_PID     = 0x0aff; // ASR
00029     const uint16_t RS400_MM_PID     = 0x0b00; // PSR
00030     const uint16_t RS430_MM_RGB_PID = 0x0b01; // AWGCT
00031     const uint16_t RS460_PID        = 0x0b03; // DS5U
00032     const uint16_t RS435_RGB_PID    = 0x0b07; // AWGC
00033     const uint16_t RS435i_RGB_PID   = 0x0B3A; // AWGC_MM
00034     const uint16_t RS405_PID        = 0x0b0c; // DS5U
00035     const uint16_t RS_T265_PID      = 0x0b37; // 
00036     
00037 
00038     const bool ALIGN_DEPTH    = false;
00039     const bool POINTCLOUD     = false;
00040     const bool ALLOW_NO_TEXTURE_POINTS = false;
00041     const bool SYNC_FRAMES    = false;
00042 
00043     const int IMAGE_WIDTH     = 640;
00044     const int IMAGE_HEIGHT    = 480;
00045     const int IMAGE_FPS       = 30;
00046 
00047     const int IMU_FPS         = 0;
00048 
00049 
00050     const bool ENABLE_DEPTH   = true;
00051     const bool ENABLE_INFRA1  = true;
00052     const bool ENABLE_INFRA2  = true;
00053     const bool ENABLE_COLOR   = true;
00054     const bool ENABLE_FISHEYE = true;
00055     const bool ENABLE_IMU     = true;
00056     const bool HOLD_BACK_IMU_FOR_FRAMES = false;
00057     const bool PUBLISH_ODOM_TF = true;
00058 
00059 
00060     const std::string DEFAULT_BASE_FRAME_ID            = "camera_link";
00061     const std::string DEFAULT_ODOM_FRAME_ID            = "odom_frame";
00062     const std::string DEFAULT_DEPTH_FRAME_ID           = "camera_depth_frame";
00063     const std::string DEFAULT_INFRA1_FRAME_ID          = "camera_infra1_frame";
00064     const std::string DEFAULT_INFRA2_FRAME_ID          = "camera_infra2_frame";
00065     const std::string DEFAULT_COLOR_FRAME_ID           = "camera_color_frame";
00066     const std::string DEFAULT_FISHEYE_FRAME_ID         = "camera_fisheye_frame";
00067     const std::string DEFAULT_IMU_FRAME_ID             = "camera_imu_frame";
00068 
00069     const std::string DEFAULT_DEPTH_OPTICAL_FRAME_ID   = "camera_depth_optical_frame";
00070     const std::string DEFAULT_INFRA1_OPTICAL_FRAME_ID  = "camera_infra1_optical_frame";
00071     const std::string DEFAULT_INFRA2_OPTICAL_FRAME_ID  = "camera_infra2_optical_frame";
00072     const std::string DEFAULT_COLOR_OPTICAL_FRAME_ID   = "camera_color_optical_frame";
00073     const std::string DEFAULT_FISHEYE_OPTICAL_FRAME_ID = "camera_fisheye_optical_frame";
00074     const std::string DEFAULT_ACCEL_OPTICAL_FRAME_ID   = "camera_accel_optical_frame";
00075     const std::string DEFAULT_GYRO_OPTICAL_FRAME_ID    = "camera_gyro_optical_frame";
00076     const std::string DEFAULT_IMU_OPTICAL_FRAME_ID     = "camera_imu_optical_frame";
00077 
00078     const std::string DEFAULT_ALIGNED_DEPTH_TO_COLOR_FRAME_ID = "camera_aligned_depth_to_color_frame";
00079     const std::string DEFAULT_ALIGNED_DEPTH_TO_INFRA1_FRAME_ID = "camera_aligned_depth_to_infra1_frame";
00080     const std::string DEFAULT_ALIGNED_DEPTH_TO_INFRA2_FRAME_ID = "camera_aligned_depth_to_infra2_frame";
00081     const std::string DEFAULT_ALIGNED_DEPTH_TO_FISHEYE_FRAME_ID = "camera_aligned_depth_to_fisheye_frame";
00082 
00083     const std::string DEFAULT_UNITE_IMU_METHOD         = "";
00084     const std::string DEFAULT_FILTERS                  = "";
00085     const std::string DEFAULT_TOPIC_ODOM_IN            = "";
00086 
00087     const float ROS_DEPTH_SCALE = 0.001;
00088     using stream_index_pair = std::pair<rs2_stream, int>;
00089 }  // namespace realsense2_camera


realsense2_camera
Author(s): Sergey Dorodnicov , Doron Hirshberg
autogenerated on Sat Jul 6 2019 03:30:09