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=falsemaster
parent
35ad459bd9
commit
0d65d13cd8
|
@ -17,13 +17,13 @@
|
||||||
<launch>
|
<launch>
|
||||||
<node name="rviz" pkg="rviz" type="rviz" required="true"
|
<node name="rviz" pkg="rviz" type="rviz" required="true"
|
||||||
args="-d $(find cartographer_ros)/configuration_files/demo_2d.rviz" />
|
args="-d $(find cartographer_ros)/configuration_files/demo_2d.rviz" />
|
||||||
<node name="cartographer_offline_node" pkg="cartographer_ros"
|
<node name="cartographer_node" pkg="cartographer_ros"
|
||||||
type="cartographer_offline_node" args="
|
type="cartographer_node" args="
|
||||||
-configuration_directory $(find cartographer_ros)/configuration_files
|
-configuration_directory $(find cartographer_ros)/configuration_files
|
||||||
-configuration_basenames visualize_pbstream.lua
|
-configuration_basename visualize_pbstream.lua
|
||||||
-keep_running=true
|
|
||||||
-load_state_filename $(arg pbstream_filename)
|
-load_state_filename $(arg pbstream_filename)
|
||||||
-load_frozen_state=false"
|
-load_frozen_state=false
|
||||||
|
-start_trajectory_with_default_topics=false"
|
||||||
output="screen">
|
output="screen">
|
||||||
</node>
|
</node>
|
||||||
</launch>
|
</launch>
|
||||||
|
|
Loading…
Reference in New Issue