22 #include "cartographer/ground_truth/proto/relations.pb.h" 25 #include "cartographer/mapping/proto/pose_graph.pb.h" 27 #include "gflags/gflags.h" 28 #include "glog/logging.h" 31 pose_graph_filename,
"",
32 "Proto stream file containing the pose graph used to generate ground truth " 34 DEFINE_string(output_filename,
"",
"File to write the ground truth proto to.");
36 "Minimum covered distance in meters before a loop closure is " 37 "considered a candidate for autogenerated ground truth.");
39 "Distance in meters beyond which constraints are considered " 42 "Distance in radians beyond which constraints are considered " 46 namespace ground_truth {
49 std::vector<double> ComputeCoveredDistance(
50 const mapping::proto::Trajectory& trajectory) {
51 std::vector<double> covered_distance;
52 covered_distance.push_back(0.);
53 CHECK_GT(trajectory.node_size(), 0)
54 <<
"Trajectory does not contain any nodes.";
55 for (
int i = 1; i < trajectory.node_size(); ++i) {
58 covered_distance.push_back(
59 covered_distance.back() +
60 (last_pose.inverse() * this_pose).translation().norm());
62 return covered_distance;
69 std::vector<int> ComputeSubmapRepresentativeNode(
70 const mapping::proto::PoseGraph& pose_graph) {
71 std::vector<int> submap_to_node_index;
72 for (
const auto& constraint : pose_graph.constraint()) {
73 if (constraint.tag() !=
74 mapping::proto::PoseGraph::Constraint::INTRA_SUBMAP) {
77 CHECK_EQ(constraint.submap_id().trajectory_id(), 0);
78 CHECK_EQ(constraint.node_id().trajectory_id(), 0);
80 const int next_submap_index =
static_cast<int>(submap_to_node_index.size());
81 const int submap_index = constraint.submap_id().submap_index();
82 if (submap_index <= next_submap_index) {
86 CHECK_EQ(submap_index, next_submap_index + 1);
87 submap_to_node_index.push_back(constraint.node_id().node_index());
89 return submap_to_node_index;
92 proto::GroundTruth GenerateGroundTruth(
93 const mapping::proto::PoseGraph& pose_graph,
94 const double min_covered_distance,
const double outlier_threshold_meters,
95 const double outlier_threshold_radians) {
96 const mapping::proto::Trajectory& trajectory = pose_graph.trajectory(0);
97 const std::vector<double> covered_distance =
98 ComputeCoveredDistance(trajectory);
100 const std::vector<int> submap_to_node_index =
101 ComputeSubmapRepresentativeNode(pose_graph);
103 int num_outliers = 0;
104 proto::GroundTruth ground_truth;
105 for (
const auto& constraint : pose_graph.constraint()) {
107 if (constraint.tag() ==
108 mapping::proto::PoseGraph::Constraint::INTRA_SUBMAP) {
114 CHECK_EQ(constraint.submap_id().trajectory_id(), 0);
115 CHECK_EQ(constraint.node_id().trajectory_id(), 0);
116 if (constraint.submap_id().submap_index() >=
117 static_cast<int>(submap_to_node_index.size())) {
120 const int matched_node = constraint.node_id().node_index();
121 const int representative_node =
122 submap_to_node_index.at(constraint.submap_id().submap_index());
125 double covered_distance_in_constraint =
126 std::abs(covered_distance.at(matched_node) -
127 covered_distance.at(representative_node));
128 if (covered_distance_in_constraint < min_covered_distance) {
139 solution_pose1.
inverse() * solution_pose2;
142 trajectory.submap(constraint.submap_id().submap_index()).
pose());
144 solution_pose1.
inverse() * submap_solution;
148 submap_solution_to_node_solution * node_to_submap_constraint;
152 if (error.
translation().norm() > outlier_threshold_meters ||
157 auto*
const new_relation = ground_truth.add_relation();
158 new_relation->set_timestamp1(
159 trajectory.node(representative_node).timestamp());
160 new_relation->set_timestamp2(trajectory.node(matched_node).timestamp());
162 new_relation->set_covered_distance(covered_distance_in_constraint);
164 LOG(INFO) <<
"Generated " << ground_truth.relation_size()
165 <<
" relations and ignored " << num_outliers <<
" outliers.";
169 void Run(
const std::string& pose_graph_filename,
170 const std::string& output_filename,
const double min_covered_distance,
171 const double outlier_threshold_meters,
172 const double outlier_threshold_radians) {
173 LOG(INFO) <<
"Reading pose graph from '" << pose_graph_filename <<
"'...";
174 mapping::proto::PoseGraph pose_graph =
177 LOG(INFO) <<
"Autogenerating ground truth relations...";
178 const proto::GroundTruth ground_truth =
179 GenerateGroundTruth(pose_graph, min_covered_distance,
180 outlier_threshold_meters, outlier_threshold_radians);
181 LOG(INFO) <<
"Writing " << ground_truth.relation_size() <<
" relations to '" 182 << output_filename <<
"'.";
184 std::ofstream output_stream(output_filename,
185 std::ios_base::out | std::ios_base::binary);
186 CHECK(ground_truth.SerializeToOstream(&output_stream))
187 <<
"Could not serialize ground truth data.";
188 output_stream.close();
189 CHECK(output_stream) <<
"Could not write ground truth data.";
197 int main(
int argc,
char** argv) {
198 google::InitGoogleLogging(argv[0]);
199 FLAGS_logtostderr =
true;
200 google::SetUsageMessage(
202 "This program semi-automatically generates ground truth data from a\n" 203 "pose graph proto.\n" 205 "The input should contain a single trajectory and should have been\n" 206 "manually assessed to be correctly loop closed. Small local distortions\n" 207 "are acceptable if they are tiny compared to the errors we want to\n" 208 "assess using the generated ground truth data.\n" 210 "All loop closure constraints separated by long covered distance are\n" 211 "included in the output. Outliers are removed.\n");
212 google::ParseCommandLineFlags(&argc, &argv,
true);
214 if (FLAGS_pose_graph_filename.empty() || FLAGS_output_filename.empty()) {
215 google::ShowUsageWithFlagsRestrict(argv[0],
"autogenerate_ground_truth");
219 FLAGS_pose_graph_filename, FLAGS_output_filename,
220 FLAGS_min_covered_distance, FLAGS_outlier_threshold_meters,
221 FLAGS_outlier_threshold_radians);
DEFINE_double(min_covered_distance, 100., "Minimum covered distance in meters before a loop closure is " "considered a candidate for autogenerated ground truth.")
mapping::proto::PoseGraph DeserializePoseGraphFromFile(const std::string &file_name)
void Run(const std::string &configuration_directory, const std::string &configuration_basename)
DEFINE_string(pose_graph_filename, "", "Proto stream file containing the pose graph used to generate ground truth " "data.")
int main(int argc, char **argv)