From 0d65d13cd8fdeef6fe51686994cf78fa49c7ead1 Mon Sep 17 00:00:00 2001 From: Michael Grupp Date: Wed, 16 Jan 2019 12:46:10 +0100 Subject: [PATCH] Don't run final optimization in visualize_pbstream.launch (#1157) * Don't run final optimization in visualize_pbstream.launch Replaces the offline node with the normal node. The problem is that the offline node immediately runs a final optimization with `visualize_pbstream.lua`, which is most likely not the configuration that was used to generate the pbstream. This can lead to effects like distortions in the map e.g. due to different weights, even though the actual saved state is fine. * Drop all /echoes or /imu messages. * Use -start_trajectory_with_default_topics=false --- cartographer_ros/launch/visualize_pbstream.launch | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/cartographer_ros/launch/visualize_pbstream.launch b/cartographer_ros/launch/visualize_pbstream.launch index 764f5ff..cf5b7e0 100644 --- a/cartographer_ros/launch/visualize_pbstream.launch +++ b/cartographer_ros/launch/visualize_pbstream.launch @@ -17,13 +17,13 @@ -