node_main.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2016 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
18 #include "cartographer_ros/node.h"
21 #include "gflags/gflags.h"
23 
24 DEFINE_string(configuration_directory, "",
25  "First directory in which configuration files are searched, "
26  "second is always the Cartographer installation to allow "
27  "including files from there.");
28 DEFINE_string(configuration_basename, "",
29  "Basename, i.e. not containing any directory prefix, of the "
30  "configuration file.");
31 DEFINE_string(load_state_filename, "",
32  "If non-empty, filename of a .pbstream file to load, containing "
33  "a saved SLAM state.");
34 DEFINE_bool(load_frozen_state, true,
35  "Load the saved state as frozen (non-optimized) trajectories.");
37  start_trajectory_with_default_topics, true,
38  "Enable to immediately start the first trajectory with default topics.");
40  save_state_filename, "",
41  "If non-empty, serialize state and write it to disk before shutting down.");
42 
43 namespace cartographer_ros {
44 namespace {
45 
46 void Run() {
47  constexpr double kTfBufferCacheTimeInSeconds = 10.;
48  tf2_ros::Buffer tf_buffer{::ros::Duration(kTfBufferCacheTimeInSeconds)};
49  tf2_ros::TransformListener tf(tf_buffer);
50  NodeOptions node_options;
51  TrajectoryOptions trajectory_options;
52  std::tie(node_options, trajectory_options) =
53  LoadOptions(FLAGS_configuration_directory, FLAGS_configuration_basename);
54 
55  auto map_builder =
56  cartographer::common::make_unique<cartographer::mapping::MapBuilder>(
57  node_options.map_builder_options);
58  Node node(node_options, std::move(map_builder), &tf_buffer);
59  if (!FLAGS_load_state_filename.empty()) {
60  node.LoadState(FLAGS_load_state_filename, FLAGS_load_frozen_state);
61  }
62 
63  if (FLAGS_start_trajectory_with_default_topics) {
64  node.StartTrajectoryWithDefaultTopics(trajectory_options);
65  }
66 
67  ::ros::spin();
68 
69  node.FinishAllTrajectories();
70  node.RunFinalOptimization();
71 
72  if (!FLAGS_save_state_filename.empty()) {
73  node.SerializeState(FLAGS_save_state_filename);
74  }
75 }
76 
77 } // namespace
78 } // namespace cartographer_ros
79 
80 int main(int argc, char** argv) {
81  google::InitGoogleLogging(argv[0]);
82  google::ParseCommandLineFlags(&argc, &argv, true);
83 
84  CHECK(!FLAGS_configuration_directory.empty())
85  << "-configuration_directory is missing.";
86  CHECK(!FLAGS_configuration_basename.empty())
87  << "-configuration_basename is missing.";
88 
89  ::ros::init(argc, argv, "cartographer_node");
90  ::ros::start();
91 
93  cartographer_ros::Run();
94  ::ros::shutdown();
95 }
DEFINE_bool(load_frozen_state, true, "Load the saved state as frozen (non-optimized) trajectories.")
std::tuple< NodeOptions, TrajectoryOptions > LoadOptions(const std::string &configuration_directory, const std::string &configuration_basename)
Definition: node_options.cc:46
int main(int argc, char **argv)
Definition: node_main.cc:80
DEFINE_string(configuration_directory, "", "First directory in which configuration files are searched, " "second is always the Cartographer installation to allow " "including files from there.")
void Run(const std::string &configuration_directory, const std::string &configuration_basename)
tf2_ros::Buffer * tf_buffer


cartographer_ros
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:06:05