Skip to content

Commit

Permalink
removing dead code
Browse files Browse the repository at this point in the history
  • Loading branch information
remibettan committed Dec 12, 2024
1 parent 06e7d8c commit 7f888a5
Show file tree
Hide file tree
Showing 2 changed files with 0 additions and 40 deletions.
3 changes: 0 additions & 3 deletions realsense2_camera/include/ros_sensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,6 @@ namespace realsense2_camera
~RosSensor();
void registerSensorParameters();
bool getUpdatedProfiles(std::vector<rs2::stream_profile>& wanted_profiles);
void runFirstFrameInitialization();
virtual bool start(const std::vector<rs2::stream_profile>& profiles);
void stop();
rmw_qos_profile_t getQOS(const stream_index_pair& sip) const;
Expand Down Expand Up @@ -114,8 +113,6 @@ namespace realsense2_camera
std::function<void(rs2::frame)> _frame_callback;
SensorParams _params;
std::function<void()> _update_sensor_func, _hardware_reset_func;
bool _is_first_frame;
std::vector<std::function<void()> > _first_frame_functions_stack;
std::vector<std::shared_ptr<ProfilesManager> > _profile_managers;
rs2::region_of_interest _auto_exposure_roi;
std::vector<std::string> _parameters_names;
Expand Down
37 changes: 0 additions & 37 deletions realsense2_camera/src/ros_sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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};
Expand Down Expand Up @@ -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<stream_profile>& profiles)
{
if (get_active_streams().size() > 0)
Expand Down

0 comments on commit 7f888a5

Please sign in to comment.