From 12e86ae22a43819bce0f30b6c2ec0a1e10615ef3 Mon Sep 17 00:00:00 2001 From: Viktor Walter Date: Fri, 22 Mar 2024 14:04:14 +0100 Subject: [PATCH] Adding explanation --- src/detector.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/detector.cpp b/src/detector.cpp index dd3b478..dbb258a 100644 --- a/src/detector.cpp +++ b/src/detector.cpp @@ -239,12 +239,6 @@ class UVDARDetector : public nodelet::Nodelet{ return; } - double initial_delay = 5.0; //seconds - if ((ros::Time::now() - initial_delay_start_).toSec() < initial_delay){ - ROS_WARN_STREAM_THROTTLE(1.0, "[UVDARDetector]: Ignoring message for "<< initial_delay <<"s..."); - return; - } - if (!uvdf_was_initialized_){ if (!uvdf_->initDelayed(image->image)){ ROS_WARN_STREAM_THROTTLE(1.0,"[UVDARDetector]: Failed to initialize, dropping message..."); @@ -254,6 +248,12 @@ class UVDARDetector : public nodelet::Nodelet{ uvdf_was_initialized_ = true; } + double initial_delay = 5.0; //seconds. This delay is necessary to avoid strange segmentation faults with software rendering backend for OpenGL used in the buildfarm testing. + if ((ros::Time::now() - initial_delay_start_).toSec() < initial_delay){ + ROS_WARN_STREAM_THROTTLE(1.0, "[UVDARDetector]: Ignoring message for "<< initial_delay <<"s..."); + return; + } + if (!initialized_){ ROS_WARN_STREAM_THROTTLE(1.0,"[UVDARDetector]: Not yet initialized, dropping message...");