From 7f888a58d6793c7c8fffaf5701dedce700ffdc64 Mon Sep 17 00:00:00 2001 From: Remi Bettan Date: Thu, 12 Dec 2024 14:58:22 +0200 Subject: [PATCH] removing dead code --- realsense2_camera/include/ros_sensor.h | 3 --- realsense2_camera/src/ros_sensor.cpp | 37 -------------------------- 2 files changed, 40 deletions(-) diff --git a/realsense2_camera/include/ros_sensor.h b/realsense2_camera/include/ros_sensor.h index 57d224300e..67d7000e7e 100644 --- a/realsense2_camera/include/ros_sensor.h +++ b/realsense2_camera/include/ros_sensor.h @@ -86,7 +86,6 @@ namespace realsense2_camera ~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; @@ -114,8 +113,6 @@ namespace realsense2_camera 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; diff --git a/realsense2_camera/src/ros_sensor.cpp b/realsense2_camera/src/ros_sensor.cpp index 53c6d4efe4..3cfa59ef99 100644 --- a/realsense2_camera/src/ros_sensor.cpp +++ b/realsense2_camera/src/ros_sensor.cpp @@ -53,13 +53,11 @@ RosSensor::RosSensor(rs2::sensor sensor, _params(parameters, _logger), _update_sensor_func(update_sensor_func), _hardware_reset_func(hardware_reset_func), - _is_first_frame(true), _diagnostics_updater(diagnostics_updater), _force_image_default_qos(force_image_default_qos) { _frame_callback = [this](rs2::frame frame) { - runFirstFrameInitialization(); auto stream_type = frame.get_profile().stream_type(); auto stream_index = frame.get_profile().stream_index(); stream_index_pair sip{stream_type, stream_index}; @@ -236,41 +234,6 @@ void RosSensor::registerSensorParameters() } } -void RosSensor::runFirstFrameInitialization() -{ - if (_is_first_frame) - { - ROS_DEBUG_STREAM("runFirstFrameInitialization: " << _first_frame_functions_stack.size()); - _is_first_frame = false; - if (!_first_frame_functions_stack.empty()) - { - std::thread t = std::thread([=]() - { - try - { - while (!_first_frame_functions_stack.empty()) - { - _first_frame_functions_stack.back()(); - _first_frame_functions_stack.pop_back(); - } - } - catch(const std::exception& e) - { - std::cerr << "runFirstFrameInitialization(): " << e.what() << '\n'; - throw e; - } - catch(...) - { - std::cerr << "runFirstFrameInitialization()!!!" << std::endl; - throw; - } - - }); - t.detach(); - } - } -} - bool RosSensor::start(const std::vector& profiles) { if (get_active_streams().size() > 0)