From 530acb598498da65b68d6da1fb1b242e34afecc5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Juraj=20Or=C5=A1uli=C4=87?= Date: Fri, 19 Oct 2018 10:44:42 +0200 Subject: [PATCH] Decrease asset writer progress log period (#1044) With two 20 Hz lidars and a 200 Hz IMU, the progress reports were outputted every 500 seconds, which is really too sparse to be useful. Decrease this by a factor of 10. --- cartographer_ros/cartographer_ros/assets_writer.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cartographer_ros/cartographer_ros/assets_writer.cc b/cartographer_ros/cartographer_ros/assets_writer.cc index 688168b..1ca3e09 100644 --- a/cartographer_ros/cartographer_ros/assets_writer.cc +++ b/cartographer_ros/cartographer_ros/assets_writer.cc @@ -251,7 +251,7 @@ void AssetsWriter::Run(const std::string& configuration_directory, delayed_messages.pop_front(); } delayed_messages.push_back(message); - LOG_EVERY_N(INFO, 100000) + LOG_EVERY_N(INFO, 10000) << "Processed " << (message.getTime() - begin_time).toSec() << " of " << duration_in_seconds << " bag time seconds..."; }