constants.h 4.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106
  1. // Copyright 2023 RealSense, Inc. All Rights Reserved.
  2. //
  3. // Licensed under the Apache License, Version 2.0 (the "License");
  4. // you may not use this file except in compliance with the License.
  5. // You may obtain a copy of the License at
  6. //
  7. // http://www.apache.org/licenses/LICENSE-2.0
  8. //
  9. // Unless required by applicable law or agreed to in writing, software
  10. // distributed under the License is distributed on an "AS IS" BASIS,
  11. // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  12. // See the License for the specific language governing permissions and
  13. // limitations under the License.
  14. #pragma once
  15. #include <string>
  16. #include "ros_node_base.h"
  17. #define REALSENSE_ROS_MAJOR_VERSION 4
  18. #define REALSENSE_ROS_MINOR_VERSION 57
  19. #define REALSENSE_ROS_PATCH_VERSION 4
  20. #define STRINGIFY(arg) #arg
  21. #define VAR_ARG_STRING(arg) STRINGIFY(arg)
  22. /* Return version in "X.Y.Z" format */
  23. #define REALSENSE_ROS_VERSION_STR (VAR_ARG_STRING(REALSENSE_ROS_MAJOR_VERSION.REALSENSE_ROS_MINOR_VERSION.REALSENSE_ROS_PATCH_VERSION))
  24. #define ROS_DEBUG(...) RCLCPP_DEBUG(_logger, __VA_ARGS__)
  25. #define ROS_INFO(...) RCLCPP_INFO(_logger, __VA_ARGS__)
  26. #define ROS_WARN(...) RCLCPP_WARN(_logger, __VA_ARGS__)
  27. #define ROS_ERROR(...) RCLCPP_ERROR(_logger, __VA_ARGS__)
  28. // Based on: https://docs.ros2.org/latest/api/rclcpp/logging_8hpp.html
  29. #define ROS_DEBUG_STREAM(msg) RCLCPP_DEBUG_STREAM(_logger, msg)
  30. #define ROS_INFO_STREAM(msg) RCLCPP_INFO_STREAM(_logger, msg)
  31. #define ROS_WARN_STREAM(msg) RCLCPP_WARN_STREAM(_logger, msg)
  32. #define ROS_ERROR_STREAM(msg) RCLCPP_ERROR_STREAM(_logger, msg)
  33. #define ROS_FATAL_STREAM(msg) RCLCPP_FATAL_STREAM(_logger, msg)
  34. #define ROS_DEBUG_STREAM_ONCE(msg) RCLCPP_DEBUG_STREAM_ONCE(_logger, msg)
  35. #define ROS_INFO_STREAM_ONCE(msg) RCLCPP_INFO_STREAM_ONCE(_logger, msg)
  36. #define ROS_WARN_STREAM_COND(cond, msg) RCLCPP_WARN_STREAM_EXPRESSION(_logger, cond, msg)
  37. #define ROS_WARN_ONCE(msg) RCLCPP_WARN_ONCE(_logger, msg)
  38. #define ROS_WARN_COND(cond, ...) RCLCPP_WARN_EXPRESSION(_logger, cond, __VA_ARGS__)
  39. namespace realsense2_camera
  40. {
  41. const uint16_t RS400_PID = 0x0ad1; // PSR
  42. const uint16_t RS410_PID = 0x0ad2; // ASR
  43. const uint16_t RS415_PID = 0x0ad3; // ASRC
  44. const uint16_t RS430_PID = 0x0ad4; // AWG
  45. const uint16_t RS430_MM_PID = 0x0ad5; // AWGT
  46. const uint16_t RS_USB2_PID = 0x0ad6; // USB2
  47. const uint16_t RS420_PID = 0x0af6; // PWG
  48. const uint16_t RS421_PID = 0x1155; // D421
  49. const uint16_t RS420_MM_PID = 0x0afe; // PWGT
  50. const uint16_t RS410_MM_PID = 0x0aff; // ASR
  51. const uint16_t RS400_MM_PID = 0x0b00; // PSR
  52. const uint16_t RS430_MM_RGB_PID = 0x0b01; // AWGCT
  53. const uint16_t RS460_PID = 0x0b03; // DS5U
  54. const uint16_t RS435_RGB_PID = 0x0b07; // AWGC
  55. const uint16_t RS435i_RGB_PID = 0x0B3A; // AWGC_MM
  56. const uint16_t RS416_RGB_PID = 0x0B52; // F416 RGB
  57. const uint16_t RS430i_PID = 0x0b4b; // D430i
  58. const uint16_t RS405_PID = 0x0B5B; // DS5U
  59. const uint16_t RS455_PID = 0x0B5C; // D455
  60. const uint16_t RS457_PID = 0xABCD; // D457
  61. const uint16_t RS_D585_PID = 0x0B6A; // D585, D for depth
  62. const uint16_t RS_D585S_PID = 0x0B6B; // D585S, S for safety
  63. const uint16_t RS555_PID = 0x0B56; // D555
  64. const uint16_t RS436_PID = 0x1156; // D436
  65. const bool ALLOW_NO_TEXTURE_POINTS = false;
  66. const bool ORDERED_PC = false;
  67. const bool SYNC_FRAMES = false;
  68. const bool ENABLE_RGBD = false;
  69. const bool PUBLISH_TF = true;
  70. const double TF_PUBLISH_RATE = 0; // Static transform
  71. const double DIAGNOSTICS_PERIOD = 0.0;
  72. const std::string IMAGE_QOS = "SYSTEM_DEFAULT";
  73. const std::string DEFAULT_QOS = "DEFAULT";
  74. const std::string HID_QOS = "SENSOR_DATA";
  75. const bool HOLD_BACK_IMU_FOR_FRAMES = false;
  76. const std::string DEFAULT_BASE_FRAME_ID = "link";
  77. const std::string DEFAULT_IMU_OPTICAL_FRAME_ID = "camera_imu_optical_frame";
  78. const float ROS_DEPTH_SCALE = 0.001;
  79. static const rmw_qos_profile_t rmw_qos_profile_latched =
  80. {
  81. RMW_QOS_POLICY_HISTORY_KEEP_LAST,
  82. 1,
  83. RMW_QOS_POLICY_RELIABILITY_RELIABLE,
  84. RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL,
  85. RMW_QOS_DEADLINE_DEFAULT,
  86. RMW_QOS_LIFESPAN_DEFAULT,
  87. RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT,
  88. RMW_QOS_LIVELINESS_LEASE_DURATION_DEFAULT,
  89. false
  90. };
  91. } // namespace realsense2_camera