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" 40 pose_graph_filename,
"",
41 "Proto stream file containing the pose graph used to assess quality.");
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.");
48 "Enable exporting relation metrics as comma-separated values to " 49 "[pose_graph_filename].relation_metrics.csv");
52 namespace ground_truth {
69 (pose1.inverse() * pose2) * expected.
inverse();
74 std::string MeanAndStdDevString(
const std::vector<double>& values) {
75 CHECK_GE(values.size(), 2);
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);
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());
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(
100 squared_rotational_errors_degrees.push_back(
103 return "Abs translational error " +
104 MeanAndStdDevString(translational_errors) +
106 "Sqr translational error " +
107 MeanAndStdDevString(squared_translational_errors) +
109 "Abs rotational error " +
110 MeanAndStdDevString(rotational_errors_degrees) +
112 "Sqr rotational error " +
113 MeanAndStdDevString(squared_rotational_errors_degrees) +
" deg^2\n";
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 +
123 relation_errors_file.open(relation_metrics_filename);
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();
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 =
138 double squared_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";
153 relation_errors_file.close();
157 const transform::TransformInterpolationBuffer&
158 transform_interpolation_buffer,
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);
167 return transform_interpolation_buffer.Lookup(
168 transform_interpolation_buffer.latest_time());
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 =
179 const transform::TransformInterpolationBuffer transform_interpolation_buffer(
180 pose_graph.trajectory(0));
182 proto::GroundTruth ground_truth;
183 if (read_text_file_with_unix_timestamps) {
184 LOG(INFO) <<
"Reading relations from '" << relations_filename <<
"'...";
187 LOG(INFO) <<
"Reading ground truth from '" << relations_filename <<
"'...";
188 std::ifstream ground_truth_stream(relations_filename.c_str(),
190 CHECK(ground_truth.ParseFromIstream(&ground_truth_stream));
193 std::vector<Error> errors;
194 for (
const auto& relation : ground_truth.relation()) {
196 LookupTransform(transform_interpolation_buffer,
199 LookupTransform(transform_interpolation_buffer,
203 errors.push_back(ComputeError(pose1, pose2, expected));
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);
212 LOG(INFO) <<
"Result:\n" << StatisticsString(errors);
219 int main(
int argc,
char** argv) {
220 google::InitGoogleLogging(argv[0]);
221 FLAGS_logtostderr =
true;
222 google::SetUsageMessage(
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);
230 if (FLAGS_pose_graph_filename.empty() || FLAGS_relations_filename.empty()) {
231 google::ShowUsageWithFlagsRestrict(argv[0],
"compute_relations_metrics");
236 FLAGS_pose_graph_filename, FLAGS_relations_filename,
237 FLAGS_read_text_file_with_unix_timestamps, FLAGS_write_relation_metrics);
double translational_squared
proto::GroundTruth ReadRelationsTextFile(const std::string &relations_filename)
constexpr double RadToDeg(double rad)
UniversalTimeScaleClock::time_point Time
Time FromUniversal(const int64 ticks)
double rotational_squared
int main(int argc, char **argv)
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.")
void Run(const std::string &configuration_directory, const std::string &configuration_basename)