From 92fefe3f7eee7daee0686b846f32efcdd93b0ea0 Mon Sep 17 00:00:00 2001 From: Jihoon Lee Date: Fri, 29 Sep 2017 14:44:07 +0200 Subject: [PATCH] Serialize state before shutdown (#502) --- cartographer_ros/cartographer_ros/node_main.cc | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/cartographer_ros/cartographer_ros/node_main.cc b/cartographer_ros/cartographer_ros/node_main.cc index 9106820..c05f355 100644 --- a/cartographer_ros/cartographer_ros/node_main.cc +++ b/cartographer_ros/cartographer_ros/node_main.cc @@ -31,6 +31,8 @@ DEFINE_string(map_filename, "", "If non-empty, filename of a map to load."); DEFINE_bool( start_trajectory_with_default_topics, true, "Enable to immediately start the first trajectory with default topics."); +DEFINE_string(save_map_filename, "", + "If non-empty, serialize state and write it to disk before shutting down."); namespace cartographer_ros { namespace { @@ -57,6 +59,10 @@ void Run() { node.FinishAllTrajectories(); node.RunFinalOptimization(); + + if (!FLAGS_save_map_filename.empty()) { + node.SerializeState(FLAGS_save_map_filename); + } } } // namespace