.. _program_listing_file_include_ros_sensor.h: Program Listing for File ros_sensor.h ===================================== |exhale_lsh| :ref:`Return to documentation for file ` (``include/ros_sensor.h``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2023 Intel Corporation. All Rights Reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // // Unless required by applicable law or agreed to in writing, software // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. #pragma once #include #include #include "constants.h" #include #include #include #include #include #include #include namespace realsense2_camera { typedef std::pair stream_index_pair; class FrequencyDiagnostics { public: FrequencyDiagnostics(std::string name, int expected_frequency, std::shared_ptr updater): _name(name), _min_freq(expected_frequency), _max_freq(expected_frequency), _freq_status_param(&_min_freq, &_max_freq, 0.1, 10), _freq_status(_freq_status_param, _name), _p_updater(updater) { _p_updater->add(_freq_status); }; FrequencyDiagnostics (const FrequencyDiagnostics& other): _name(other._name), _min_freq(other._min_freq), _max_freq(other._max_freq), _freq_status_param(&_min_freq, &_max_freq, 0.1, 10), _freq_status(_freq_status_param, _name), _p_updater(other._p_updater) { _p_updater->add(_freq_status); }; ~FrequencyDiagnostics() { _p_updater->removeByName(_name); } void Tick() { _freq_status.tick(); } private: std::string _name; double _min_freq, _max_freq; diagnostic_updater::FrequencyStatusParam _freq_status_param; diagnostic_updater::FrequencyStatus _freq_status; std::shared_ptr _p_updater; }; class RosSensor : public rs2::sensor { public: RosSensor(rs2::sensor sensor, std::shared_ptr parameters, std::function frame_callback, std::function update_sensor_func, std::function hardware_reset_func, std::shared_ptr diagnostics_updater, rclcpp::Logger logger, bool force_image_default_qos = false, bool is_rosbag_file = false); ~RosSensor(); void registerSensorParameters(); bool getUpdatedProfiles(std::vector& wanted_profiles); void runFirstFrameInitialization(); virtual bool start(const std::vector& profiles); void stop(); rmw_qos_profile_t getQOS(const stream_index_pair& sip) const; rmw_qos_profile_t getInfoQOS(const stream_index_pair& sip) const; template bool is() const { return rs2::sensor::is(); } private: void setupErrorCallback(); void setParameters(bool is_rosbag_file = false); void clearParameters(); void set_sensor_auto_exposure_roi(); void registerAutoExposureROIOptions(); void UpdateSequenceIdCallback(); template void set_sensor_parameter_to_ros(rs2_option option); private: rclcpp::Logger _logger; std::function _origin_frame_callback; std::function _frame_callback; SensorParams _params; std::function _update_sensor_func, _hardware_reset_func; bool _is_first_frame; std::vector > _first_frame_functions_stack; std::vector > _profile_managers; rs2::region_of_interest _auto_exposure_roi; std::vector _parameters_names; std::shared_ptr _diagnostics_updater; std::map _frequency_diagnostics; bool _force_image_default_qos; }; }