ros_sensor.h 4.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123
  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 <librealsense2/rs.hpp>
  16. #include <librealsense2/rsutil.h>
  17. #include "constants.h"
  18. #include <map>
  19. #include "ros_node_base.h"
  20. #include <ros_utils.h>
  21. #include <sensor_params.h>
  22. #include <profile_manager.h>
  23. #include <diagnostic_updater/diagnostic_updater.hpp>
  24. #include <diagnostic_updater/update_functions.hpp>
  25. namespace realsense2_camera
  26. {
  27. typedef std::pair<rs2_stream, int> stream_index_pair;
  28. class FrequencyDiagnostics
  29. {
  30. public:
  31. FrequencyDiagnostics(std::string name, int expected_frequency, std::shared_ptr<diagnostic_updater::Updater> updater):
  32. _name(name),
  33. _min_freq(expected_frequency), _max_freq(expected_frequency),
  34. _freq_status_param(&_min_freq, &_max_freq, 0.1, 10),
  35. _freq_status(_freq_status_param, _name),
  36. _p_updater(updater)
  37. {
  38. _p_updater->add(_freq_status);
  39. };
  40. FrequencyDiagnostics (const FrequencyDiagnostics& other):
  41. _name(other._name),
  42. _min_freq(other._min_freq),
  43. _max_freq(other._max_freq),
  44. _freq_status_param(&_min_freq, &_max_freq, 0.1, 10),
  45. _freq_status(_freq_status_param, _name),
  46. _p_updater(other._p_updater)
  47. {
  48. _p_updater->add(_freq_status);
  49. };
  50. ~FrequencyDiagnostics()
  51. {
  52. _p_updater->removeByName(_name);
  53. }
  54. void Tick()
  55. {
  56. _freq_status.tick();
  57. }
  58. private:
  59. std::string _name;
  60. double _min_freq, _max_freq;
  61. diagnostic_updater::FrequencyStatusParam _freq_status_param;
  62. diagnostic_updater::FrequencyStatus _freq_status;
  63. std::shared_ptr<diagnostic_updater::Updater> _p_updater;
  64. };
  65. class RosSensor : public rs2::sensor
  66. {
  67. public:
  68. RosSensor(rs2::sensor sensor,
  69. std::shared_ptr<Parameters> parameters,
  70. std::function<void(rs2::frame)> frame_callback,
  71. std::function<void()> update_sensor_func,
  72. std::function<void()> hardware_reset_func,
  73. std::shared_ptr<diagnostic_updater::Updater> diagnostics_updater,
  74. rclcpp::Logger logger,
  75. bool force_image_default_qos = false,
  76. bool is_rosbag_file = false);
  77. ~RosSensor();
  78. void registerSensorParameters();
  79. bool getUpdatedProfiles(std::vector<rs2::stream_profile>& wanted_profiles);
  80. virtual bool start(const std::vector<rs2::stream_profile>& profiles);
  81. void stop();
  82. rmw_qos_profile_t getQOS(const stream_index_pair& sip) const;
  83. rmw_qos_profile_t getInfoQOS(const stream_index_pair& sip) const;
  84. template<class T>
  85. bool is() const
  86. {
  87. return rs2::sensor::is<T>();
  88. }
  89. private:
  90. void setupErrorCallback();
  91. void setParameters(bool is_rosbag_file = false);
  92. void clearParameters();
  93. void set_sensor_auto_exposure_roi();
  94. void registerAutoExposureROIOptions();
  95. void UpdateSequenceIdCallback();
  96. template<class T>
  97. void set_sensor_parameter_to_ros(rs2_option option);
  98. private:
  99. rclcpp::Logger _logger;
  100. std::function<void(rs2::frame)> _origin_frame_callback;
  101. std::function<void(rs2::frame)> _frame_callback;
  102. SensorParams _params;
  103. std::function<void()> _update_sensor_func, _hardware_reset_func;
  104. std::vector<std::shared_ptr<ProfilesManager> > _profile_managers;
  105. rs2::region_of_interest _auto_exposure_roi;
  106. std::vector<std::string> _parameters_names;
  107. std::shared_ptr<diagnostic_updater::Updater> _diagnostics_updater;
  108. std::map<stream_index_pair, FrequencyDiagnostics> _frequency_diagnostics;
  109. bool _force_image_default_qos;
  110. };
  111. }