compute_relations_metrics_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 
17 #include <algorithm>
18 #include <cmath>
19 #include <fstream>
20 #include <iomanip>
21 #include <iostream>
22 #include <sstream>
23 #include <string>
24 #include <vector>
25 
28 #include "cartographer/ground_truth/proto/relations.pb.h"
32 #include "cartographer/mapping/proto/pose_graph.pb.h"
36 #include "gflags/gflags.h"
37 #include "glog/logging.h"
38 
40  pose_graph_filename, "",
41  "Proto stream file containing the pose graph used to assess quality.");
42 DEFINE_string(relations_filename, "",
43  "Relations file containing the ground truth.");
44 DEFINE_bool(read_text_file_with_unix_timestamps, false,
45  "Enable support for the relations text files as in the paper. "
46  "Default is to read from a GroundTruth proto file.");
47 DEFINE_bool(write_relation_metrics, false,
48  "Enable exporting relation metrics as comma-separated values to "
49  "[pose_graph_filename].relation_metrics.csv");
50 
51 namespace cartographer {
52 namespace ground_truth {
53 namespace {
54 
55 struct Error {
58 };
59 
60 // TODO(whess): This gives different results for the translational error if
61 // 'pose1' and 'pose2' are swapped and 'expected' is inverted. Consider a
62 // different way to compute translational error. Maybe just look at the
63 // absolute difference in translation norms of each relative transform as a
64 // lower bound of the translational error.
65 Error ComputeError(const transform::Rigid3d& pose1,
66  const transform::Rigid3d& pose2,
67  const transform::Rigid3d& expected) {
68  const transform::Rigid3d error =
69  (pose1.inverse() * pose2) * expected.inverse();
70  return Error{error.translation().squaredNorm(),
72 }
73 
74 std::string MeanAndStdDevString(const std::vector<double>& values) {
75  CHECK_GE(values.size(), 2);
76  const double mean =
77  std::accumulate(values.begin(), values.end(), 0.) / values.size();
78  double sum_of_squared_differences = 0.;
79  for (const double value : values) {
80  sum_of_squared_differences += common::Pow2(value - mean);
81  }
82  const double standard_deviation =
83  std::sqrt(sum_of_squared_differences / (values.size() - 1));
84  std::ostringstream out;
85  out << std::fixed << std::setprecision(5) << mean << " +/- "
86  << standard_deviation;
87  return std::string(out.str());
88 }
89 
90 std::string StatisticsString(const std::vector<Error>& errors) {
91  std::vector<double> translational_errors;
92  std::vector<double> squared_translational_errors;
93  std::vector<double> rotational_errors_degrees;
94  std::vector<double> squared_rotational_errors_degrees;
95  for (const Error& error : errors) {
96  translational_errors.push_back(std::sqrt(error.translational_squared));
97  squared_translational_errors.push_back(error.translational_squared);
98  rotational_errors_degrees.push_back(
99  common::RadToDeg(std::sqrt(error.rotational_squared)));
100  squared_rotational_errors_degrees.push_back(
101  common::Pow2(rotational_errors_degrees.back()));
102  }
103  return "Abs translational error " +
104  MeanAndStdDevString(translational_errors) +
105  " m\n"
106  "Sqr translational error " +
107  MeanAndStdDevString(squared_translational_errors) +
108  " m^2\n"
109  "Abs rotational error " +
110  MeanAndStdDevString(rotational_errors_degrees) +
111  " deg\n"
112  "Sqr rotational error " +
113  MeanAndStdDevString(squared_rotational_errors_degrees) + " deg^2\n";
114 }
115 
116 void WriteRelationMetricsToFile(const std::vector<Error>& errors,
117  const proto::GroundTruth& ground_truth,
118  const std::string& relation_metrics_filename) {
119  std::ofstream relation_errors_file;
120  std::string log_file_path;
121  LOG(INFO) << "Writing relation metrics to '" + relation_metrics_filename +
122  "'...";
123  relation_errors_file.open(relation_metrics_filename);
124  relation_errors_file
125  << "translational_error,squared_translational_error,rotational_"
126  "errors_degree,squared_rotational_errors_degree,"
127  "expected_translation_x,expected_translation_y,expected_"
128  "translation_z,expected_rotation_w,expected_rotation_x,"
129  "expected_rotation_y,expected_rotation_z,covered_distance\n";
130  for (int relation_index = 0; relation_index < ground_truth.relation_size();
131  ++relation_index) {
132  const Error& error = errors[relation_index];
133  const proto::Relation& relation = ground_truth.relation(relation_index);
134  double translational_error = std::sqrt(error.translational_squared);
135  double squared_translational_error = error.translational_squared;
136  double rotational_errors_degree =
137  common::RadToDeg(std::sqrt(error.rotational_squared));
138  double squared_rotational_errors_degree =
139  common::Pow2(rotational_errors_degree);
140  relation_errors_file << translational_error << ","
141  << squared_translational_error << ","
142  << rotational_errors_degree << ","
143  << squared_rotational_errors_degree << ","
144  << relation.expected().translation().x() << ","
145  << relation.expected().translation().y() << ","
146  << relation.expected().translation().z() << ","
147  << relation.expected().rotation().w() << ","
148  << relation.expected().rotation().x() << ","
149  << relation.expected().rotation().y() << ","
150  << relation.expected().rotation().z() << ","
151  << relation.covered_distance() << "\n";
152  }
153  relation_errors_file.close();
154 }
155 
156 transform::Rigid3d LookupTransform(
157  const transform::TransformInterpolationBuffer&
158  transform_interpolation_buffer,
159  const common::Time time) {
160  const common::Time earliest_time =
161  transform_interpolation_buffer.earliest_time();
162  if (transform_interpolation_buffer.Has(time)) {
163  return transform_interpolation_buffer.Lookup(time);
164  } else if (time < earliest_time) {
165  return transform_interpolation_buffer.Lookup(earliest_time);
166  }
167  return transform_interpolation_buffer.Lookup(
168  transform_interpolation_buffer.latest_time());
169 }
170 
171 void Run(const std::string& pose_graph_filename,
172  const std::string& relations_filename,
173  const bool read_text_file_with_unix_timestamps,
174  const bool write_relation_metrics) {
175  LOG(INFO) << "Reading pose graph from '" << pose_graph_filename << "'...";
176  mapping::proto::PoseGraph pose_graph =
177  io::DeserializePoseGraphFromFile(pose_graph_filename);
178 
179  const transform::TransformInterpolationBuffer transform_interpolation_buffer(
180  pose_graph.trajectory(0));
181 
182  proto::GroundTruth ground_truth;
183  if (read_text_file_with_unix_timestamps) {
184  LOG(INFO) << "Reading relations from '" << relations_filename << "'...";
185  ground_truth = ReadRelationsTextFile(relations_filename);
186  } else {
187  LOG(INFO) << "Reading ground truth from '" << relations_filename << "'...";
188  std::ifstream ground_truth_stream(relations_filename.c_str(),
189  std::ios::binary);
190  CHECK(ground_truth.ParseFromIstream(&ground_truth_stream));
191  }
192 
193  std::vector<Error> errors;
194  for (const auto& relation : ground_truth.relation()) {
195  const auto pose1 =
196  LookupTransform(transform_interpolation_buffer,
197  common::FromUniversal(relation.timestamp1()));
198  const auto pose2 =
199  LookupTransform(transform_interpolation_buffer,
200  common::FromUniversal(relation.timestamp2()));
201  const transform::Rigid3d expected =
202  transform::ToRigid3(relation.expected());
203  errors.push_back(ComputeError(pose1, pose2, expected));
204  }
205 
206  const std::string relation_metrics_filename =
207  pose_graph_filename + ".relation_metrics.csv";
208  if (write_relation_metrics) {
209  WriteRelationMetricsToFile(errors, ground_truth, relation_metrics_filename);
210  }
211 
212  LOG(INFO) << "Result:\n" << StatisticsString(errors);
213 }
214 
215 } // namespace
216 } // namespace ground_truth
217 } // namespace cartographer
218 
219 int main(int argc, char** argv) {
220  google::InitGoogleLogging(argv[0]);
221  FLAGS_logtostderr = true;
222  google::SetUsageMessage(
223  "\n\n"
224  "This program computes the relation based metric described in:\n"
225  "R. Kuemmerle, B. Steder, C. Dornhege, M. Ruhnke, G. Grisetti,\n"
226  "C. Stachniss, and A. Kleiner, \"On measuring the accuracy of SLAM\n"
227  "algorithms,\" Autonomous Robots, vol. 27, no. 4, pp. 387–407, 2009.");
228  google::ParseCommandLineFlags(&argc, &argv, true);
229 
230  if (FLAGS_pose_graph_filename.empty() || FLAGS_relations_filename.empty()) {
231  google::ShowUsageWithFlagsRestrict(argv[0], "compute_relations_metrics");
232  return EXIT_FAILURE;
233  }
234 
236  FLAGS_pose_graph_filename, FLAGS_relations_filename,
237  FLAGS_read_text_file_with_unix_timestamps, FLAGS_write_relation_metrics);
238 }
double translational_squared
constexpr T Pow2(T a)
Definition: math.h:50
Rigid3< double > Rigid3d
proto::GroundTruth ReadRelationsTextFile(const std::string &relations_filename)
constexpr double RadToDeg(double rad)
Definition: math.h:58
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
transform::Rigid3d ToRigid3(const proto::Rigid3d &rigid)
Definition: transform.cc:71
Time FromUniversal(const int64 ticks)
Definition: time.cc:34
static time_point time
double rotational_squared
int main(int argc, char **argv)
const Vector & translation() const
DEFINE_string(pose_graph_filename, "", "Proto stream file containing the pose graph used to assess quality.")
mapping::proto::PoseGraph DeserializePoseGraphFromFile(const std::string &file_name)
DEFINE_bool(read_text_file_with_unix_timestamps, false, "Enable support for the relations text files as in the paper. " "Default is to read from a GroundTruth proto file.")
FloatType GetAngle(const Rigid3< FloatType > &transform)
Definition: transform.h:34
void Run(const std::string &configuration_directory, const std::string &configuration_basename)


cartographer
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:00:58