From 5a2db79fc356f2754cffbc0b293ba8ae5a1feeeb Mon Sep 17 00:00:00 2001 From: Yutaka Takaoka Date: Wed, 16 Aug 2017 02:49:56 -0700 Subject: [PATCH] Add flag to start first trajectory. (#482) --- cartographer_ros/cartographer_ros/node_main.cc | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/cartographer_ros/cartographer_ros/node_main.cc b/cartographer_ros/cartographer_ros/node_main.cc index aa0fed7..9106820 100644 --- a/cartographer_ros/cartographer_ros/node_main.cc +++ b/cartographer_ros/cartographer_ros/node_main.cc @@ -28,6 +28,9 @@ DEFINE_string(configuration_basename, "", "Basename, i.e. not containing any directory prefix, of the " "configuration file."); 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."); namespace cartographer_ros { namespace { @@ -45,7 +48,10 @@ void Run() { if (!FLAGS_map_filename.empty()) { node.LoadMap(FLAGS_map_filename); } - node.StartTrajectoryWithDefaultTopics(trajectory_options); + + if (FLAGS_start_trajectory_with_default_topics) { + node.StartTrajectoryWithDefaultTopics(trajectory_options); + } ::ros::spin();