Add flag to start first trajectory. (#482)

master
Yutaka Takaoka 2017-08-16 02:49:56 -07:00 committed by Wolfgang Hess
parent cf13f76c82
commit 5a2db79fc3
1 changed files with 7 additions and 1 deletions

View File

@ -28,6 +28,9 @@ DEFINE_string(configuration_basename, "",
"Basename, i.e. not containing any directory prefix, of the " "Basename, i.e. not containing any directory prefix, of the "
"configuration file."); "configuration file.");
DEFINE_string(map_filename, "", "If non-empty, filename of a map to load."); 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 cartographer_ros {
namespace { namespace {
@ -45,7 +48,10 @@ void Run() {
if (!FLAGS_map_filename.empty()) { if (!FLAGS_map_filename.empty()) {
node.LoadMap(FLAGS_map_filename); node.LoadMap(FLAGS_map_filename);
} }
if (FLAGS_start_trajectory_with_default_topics) {
node.StartTrajectoryWithDefaultTopics(trajectory_options); node.StartTrajectoryWithDefaultTopics(trajectory_options);
}
::ros::spin(); ::ros::spin();