22 #include "cartographer/ground_truth/proto/relations.pb.h" 23 #include "cartographer/mapping/proto/sparse_pose_graph.pb.h" 25 #include "gflags/gflags.h" 26 #include "glog/logging.h" 29 pose_graph_filename,
"",
30 "File with the pose graph proto from which to generate ground truth data.");
31 DEFINE_string(output_filename,
"",
"File to write the ground truth proto to.");
33 "Minimum covered distance in meters before a loop closure is " 34 "considered a candidate for autogenerated ground truth.");
36 "Distance in meters beyond which constraints are considered " 40 namespace ground_truth {
43 std::vector<double> ComputeCoveredDistance(
44 const mapping::proto::Trajectory& trajectory) {
45 std::vector<double> covered_distance;
46 covered_distance.push_back(0.);
47 CHECK_GT(trajectory.node_size(), 0)
48 <<
"Trajectory does not contain any nodes.";
49 for (
int i = 1; i < trajectory.node_size(); ++i) {
52 covered_distance.push_back(
53 covered_distance.back() +
54 (last_pose.inverse() * this_pose).translation().norm());
56 return covered_distance;
63 std::vector<int> ComputeSubmapRepresentativeScan(
64 const mapping::proto::SparsePoseGraph& pose_graph) {
65 std::vector<int> submap_to_scan_index;
66 for (
const auto& constraint : pose_graph.constraint()) {
67 if (constraint.tag() !=
68 mapping::proto::SparsePoseGraph::Constraint::INTRA_SUBMAP) {
71 CHECK_EQ(constraint.submap_id().trajectory_id(), 0);
72 CHECK_EQ(constraint.scan_id().trajectory_id(), 0);
74 const int next_submap_index =
static_cast<int>(submap_to_scan_index.size());
75 const int submap_index = constraint.submap_id().submap_index();
76 if (submap_index <= next_submap_index) {
80 CHECK_EQ(submap_index, next_submap_index + 1);
81 submap_to_scan_index.push_back(constraint.scan_id().scan_index());
83 return submap_to_scan_index;
86 proto::GroundTruth GenerateGroundTruth(
87 const mapping::proto::SparsePoseGraph& pose_graph,
88 const double min_covered_distance,
const double outlier_threshold) {
89 const mapping::proto::Trajectory& trajectory = pose_graph.trajectory(0);
90 const std::vector<double> covered_distance =
91 ComputeCoveredDistance(trajectory);
93 const std::vector<int> submap_to_scan_index =
94 ComputeSubmapRepresentativeScan(pose_graph);
97 proto::GroundTruth ground_truth;
98 for (
const auto& constraint : pose_graph.constraint()) {
100 if (constraint.tag() ==
101 mapping::proto::SparsePoseGraph::Constraint::INTRA_SUBMAP) {
107 CHECK_EQ(constraint.submap_id().trajectory_id(), 0);
108 CHECK_EQ(constraint.scan_id().trajectory_id(), 0);
109 if (constraint.submap_id().submap_index() >=
110 static_cast<int>(submap_to_scan_index.size())) {
113 const int matched_scan = constraint.scan_id().scan_index();
114 const int representative_scan =
115 submap_to_scan_index.at(constraint.submap_id().submap_index());
118 if (std::abs(covered_distance.at(matched_scan) -
119 covered_distance.at(representative_scan)) <
120 min_covered_distance) {
126 const auto solution_pose1 =
128 const auto solution_pose2 =
130 const auto solution = solution_pose1.
inverse() * solution_pose2;
132 const auto scan_to_submap_constraint =
135 trajectory.submap(constraint.submap_id().submap_index()).
pose());
137 submap_solution * scan_to_submap_constraint * solution_pose2.
inverse();
139 if (error.translation().norm() > outlier_threshold) {
142 auto*
const new_relation = ground_truth.add_relation();
143 new_relation->set_timestamp1(
144 trajectory.node(representative_scan).timestamp());
145 new_relation->set_timestamp2(trajectory.node(matched_scan).timestamp());
148 LOG(INFO) <<
"Generated " << ground_truth.relation_size()
149 <<
" relations and ignored " << num_outliers <<
" outliers.";
153 void Run(
const string& pose_graph_filename,
const string& output_filename,
154 const double min_covered_distance,
const double outlier_threshold) {
155 LOG(INFO) <<
"Reading pose graph from '" << pose_graph_filename <<
"'...";
156 mapping::proto::SparsePoseGraph pose_graph;
158 std::ifstream stream(pose_graph_filename.c_str());
159 CHECK(pose_graph.ParseFromIstream(&stream));
160 CHECK_EQ(pose_graph.trajectory_size(), 1)
161 <<
"Only pose graphs containing a single trajectory are supported.";
163 LOG(INFO) <<
"Autogenerating ground truth relations...";
164 const proto::GroundTruth ground_truth =
165 GenerateGroundTruth(pose_graph, min_covered_distance, outlier_threshold);
166 LOG(INFO) <<
"Writing " << ground_truth.relation_size() <<
" relations to '" 167 << output_filename <<
"'.";
169 std::ofstream output_stream(output_filename,
170 std::ios_base::out | std::ios_base::binary);
171 CHECK(ground_truth.SerializeToOstream(&output_stream))
172 <<
"Could not serialize ground truth data.";
173 output_stream.close();
174 CHECK(output_stream) <<
"Could not write ground truth data.";
182 int main(
int argc,
char** argv) {
183 google::InitGoogleLogging(argv[0]);
184 FLAGS_logtostderr =
true;
185 google::SetUsageMessage(
187 "This program semi-automatically generates ground truth data from a\n" 188 "pose graph proto.\n" 190 "The input should contain a single trajectory and should have been\n" 191 "manually assessed to be correctly loop closed. Small local distortions\n" 192 "are acceptable if they are tiny compared to the errors we want to\n" 193 "assess using the generated ground truth data.\n" 195 "All loop closure constraints separated by long covered distance are\n" 196 "included in the output. Outliers are removed.\n");
197 google::ParseCommandLineFlags(&argc, &argv,
true);
199 if (FLAGS_pose_graph_filename.empty() || FLAGS_output_filename.empty()) {
200 google::ShowUsageWithFlagsRestrict(argv[0],
"autogenerate_ground_truth");
203 ::cartographer::ground_truth::Run(
204 FLAGS_pose_graph_filename, FLAGS_output_filename,
205 FLAGS_min_covered_distance, FLAGS_outlier_threshold);
DEFINE_string(pose_graph_filename,"","File with the pose graph proto from which to generate ground truth data.")
DEFINE_double(min_covered_distance, 100.,"Minimum covered distance in meters before a loop closure is ""considered a candidate for autogenerated ground truth.")
int main(int argc, char **argv)