From 4bf12a47145298b9b3cdcb871fb8c103833baa8d Mon Sep 17 00:00:00 2001 From: Tomohito Ando Date: Tue, 4 Jun 2024 18:05:32 +0900 Subject: [PATCH] fix(multi_object_tracker): calculation of detection delay diagnostics Signed-off-by: Tomohito Ando --- perception/multi_object_tracker/src/debugger.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/multi_object_tracker/src/debugger.cpp b/perception/multi_object_tracker/src/debugger.cpp index b5632a13e78fc..08394fe80f42a 100644 --- a/perception/multi_object_tracker/src/debugger.cpp +++ b/perception/multi_object_tracker/src/debugger.cpp @@ -80,7 +80,7 @@ void TrackerDebugger::checkDelay(diagnostic_updater::DiagnosticStatusWrapper & s stat.summary(diagnostic_msgs::msg::DiagnosticStatus::ERROR, "Measurement time is not set."); return; } - const double & delay = pipeline_latency_ms_; // [s] + const double & delay = pipeline_latency_ms_ / 1e3; // [s] if (delay == 0.0) { stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "Detection delay is not calculated.");