Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #include "absl/memory/memory.h"
00018 #include "cartographer/mapping/map_builder.h"
00019 #include "cartographer_ros/node.h"
00020 #include "cartographer_ros/node_options.h"
00021 #include "cartographer_ros/ros_log_sink.h"
00022 #include "gflags/gflags.h"
00023 #include "tf2_ros/transform_listener.h"
00024
00025 DEFINE_bool(collect_metrics, false,
00026 "Activates the collection of runtime metrics. If activated, the "
00027 "metrics can be accessed via a ROS service.");
00028 DEFINE_string(configuration_directory, "",
00029 "First directory in which configuration files are searched, "
00030 "second is always the Cartographer installation to allow "
00031 "including files from there.");
00032 DEFINE_string(configuration_basename, "",
00033 "Basename, i.e. not containing any directory prefix, of the "
00034 "configuration file.");
00035 DEFINE_string(load_state_filename, "",
00036 "If non-empty, filename of a .pbstream file to load, containing "
00037 "a saved SLAM state.");
00038 DEFINE_bool(load_frozen_state, true,
00039 "Load the saved state as frozen (non-optimized) trajectories.");
00040 DEFINE_bool(
00041 start_trajectory_with_default_topics, true,
00042 "Enable to immediately start the first trajectory with default topics.");
00043 DEFINE_string(
00044 save_state_filename, "",
00045 "If non-empty, serialize state and write it to disk before shutting down.");
00046
00047 namespace cartographer_ros {
00048 namespace {
00049
00050 void Run() {
00051 constexpr double kTfBufferCacheTimeInSeconds = 10.;
00052 tf2_ros::Buffer tf_buffer{::ros::Duration(kTfBufferCacheTimeInSeconds)};
00053 tf2_ros::TransformListener tf(tf_buffer);
00054 NodeOptions node_options;
00055 TrajectoryOptions trajectory_options;
00056 std::tie(node_options, trajectory_options) =
00057 LoadOptions(FLAGS_configuration_directory, FLAGS_configuration_basename);
00058
00059 auto map_builder = absl::make_unique<cartographer::mapping::MapBuilder>(
00060 node_options.map_builder_options);
00061 Node node(node_options, std::move(map_builder), &tf_buffer,
00062 FLAGS_collect_metrics);
00063 if (!FLAGS_load_state_filename.empty()) {
00064 node.LoadState(FLAGS_load_state_filename, FLAGS_load_frozen_state);
00065 }
00066
00067 if (FLAGS_start_trajectory_with_default_topics) {
00068 node.StartTrajectoryWithDefaultTopics(trajectory_options);
00069 }
00070
00071 ::ros::spin();
00072
00073 node.FinishAllTrajectories();
00074 node.RunFinalOptimization();
00075
00076 if (!FLAGS_save_state_filename.empty()) {
00077 node.SerializeState(FLAGS_save_state_filename,
00078 true );
00079 }
00080 }
00081
00082 }
00083 }
00084
00085 int main(int argc, char** argv) {
00086 google::InitGoogleLogging(argv[0]);
00087 google::ParseCommandLineFlags(&argc, &argv, true);
00088
00089 CHECK(!FLAGS_configuration_directory.empty())
00090 << "-configuration_directory is missing.";
00091 CHECK(!FLAGS_configuration_basename.empty())
00092 << "-configuration_basename is missing.";
00093
00094 ::ros::init(argc, argv, "cartographer_node");
00095 ::ros::start();
00096
00097 cartographer_ros::ScopedRosLogSink ros_log_sink;
00098 cartographer_ros::Run();
00099 ::ros::shutdown();
00100 }