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
master
Michael Grupp 2019-01-16 12:46:10 +01:00 committed by Andre Gaschler
parent 35ad459bd9
commit 0d65d13cd8
1 changed files with 5 additions and 5 deletions

View File

@ -17,13 +17,13 @@
<launch>
<node name="rviz" pkg="rviz" type="rviz" required="true"
args="-d $(find cartographer_ros)/configuration_files/demo_2d.rviz" />
<node name="cartographer_offline_node" pkg="cartographer_ros"
type="cartographer_offline_node" args="
<node name="cartographer_node" pkg="cartographer_ros"
type="cartographer_node" args="
-configuration_directory $(find cartographer_ros)/configuration_files
-configuration_basenames visualize_pbstream.lua
-keep_running=true
-configuration_basename visualize_pbstream.lua
-load_state_filename $(arg pbstream_filename)
-load_frozen_state=false"
-load_frozen_state=false
-start_trajectory_with_default_topics=false"
output="screen">
</node>
</launch>