From 764004736e49db70ab8a8d0d73189deedab98c7c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Juraj=20Or=C5=A1uli=C4=87?= Date: Wed, 5 Jul 2017 11:17:42 +0200 Subject: [PATCH] Actually delay messages. (#406) --- cartographer_ros/cartographer_ros/offline_node_main.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cartographer_ros/cartographer_ros/offline_node_main.cc b/cartographer_ros/cartographer_ros/offline_node_main.cc index acb57f9..e7faecd 100644 --- a/cartographer_ros/cartographer_ros/offline_node_main.cc +++ b/cartographer_ros/cartographer_ros/offline_node_main.cc @@ -193,7 +193,7 @@ void Run(const std::vector& bag_filenames) { while (!delayed_messages.empty() && delayed_messages.front().getTime() < - msg.getTime() + ::ros::Duration(1.)) { + msg.getTime() - ::ros::Duration(1.)) { const rosbag::MessageInstance& delayed_msg = delayed_messages.front(); const string topic = node.node_handle()->resolveName( delayed_msg.getTopic(), false /* resolve */);