compute_relations_metrics_main.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #include <algorithm>
00018 #include <cmath>
00019 #include <fstream>
00020 #include <iomanip>
00021 #include <iostream>
00022 #include <sstream>
00023 #include <string>
00024 #include <vector>
00025 
00026 #include "cartographer/common/math.h"
00027 #include "cartographer/common/port.h"
00028 #include "cartographer/ground_truth/proto/relations.pb.h"
00029 #include "cartographer/ground_truth/relations_text_file.h"
00030 #include "cartographer/io/proto_stream.h"
00031 #include "cartographer/io/proto_stream_deserializer.h"
00032 #include "cartographer/mapping/proto/pose_graph.pb.h"
00033 #include "cartographer/transform/rigid_transform.h"
00034 #include "cartographer/transform/transform.h"
00035 #include "cartographer/transform/transform_interpolation_buffer.h"
00036 #include "gflags/gflags.h"
00037 #include "glog/logging.h"
00038 
00039 DEFINE_string(
00040     pose_graph_filename, "",
00041     "Proto stream file containing the pose graph used to assess quality.");
00042 DEFINE_string(relations_filename, "",
00043               "Relations file containing the ground truth.");
00044 DEFINE_bool(read_text_file_with_unix_timestamps, false,
00045             "Enable support for the relations text files as in the paper. "
00046             "Default is to read from a GroundTruth proto file.");
00047 DEFINE_bool(write_relation_metrics, false,
00048             "Enable exporting relation metrics as comma-separated values to "
00049             "[pose_graph_filename].relation_metrics.csv");
00050 
00051 namespace cartographer {
00052 namespace ground_truth {
00053 namespace {
00054 
00055 struct Error {
00056   double translational_squared;
00057   double rotational_squared;
00058 };
00059 
00060 // TODO(whess): This gives different results for the translational error if
00061 // 'pose1' and 'pose2' are swapped and 'expected' is inverted. Consider a
00062 // different way to compute translational error. Maybe just look at the
00063 // absolute difference in translation norms of each relative transform as a
00064 // lower bound of the translational error.
00065 Error ComputeError(const transform::Rigid3d& pose1,
00066                    const transform::Rigid3d& pose2,
00067                    const transform::Rigid3d& expected) {
00068   const transform::Rigid3d error =
00069       (pose1.inverse() * pose2) * expected.inverse();
00070   return Error{error.translation().squaredNorm(),
00071                common::Pow2(transform::GetAngle(error))};
00072 }
00073 
00074 std::string MeanAndStdDevString(const std::vector<double>& values) {
00075   CHECK_GE(values.size(), 2);
00076   const double mean =
00077       std::accumulate(values.begin(), values.end(), 0.) / values.size();
00078   double sum_of_squared_differences = 0.;
00079   for (const double value : values) {
00080     sum_of_squared_differences += common::Pow2(value - mean);
00081   }
00082   const double standard_deviation =
00083       std::sqrt(sum_of_squared_differences / (values.size() - 1));
00084   std::ostringstream out;
00085   out << std::fixed << std::setprecision(5) << mean << " +/- "
00086       << standard_deviation;
00087   return std::string(out.str());
00088 }
00089 
00090 std::string StatisticsString(const std::vector<Error>& errors) {
00091   std::vector<double> translational_errors;
00092   std::vector<double> squared_translational_errors;
00093   std::vector<double> rotational_errors_degrees;
00094   std::vector<double> squared_rotational_errors_degrees;
00095   for (const Error& error : errors) {
00096     translational_errors.push_back(std::sqrt(error.translational_squared));
00097     squared_translational_errors.push_back(error.translational_squared);
00098     rotational_errors_degrees.push_back(
00099         common::RadToDeg(std::sqrt(error.rotational_squared)));
00100     squared_rotational_errors_degrees.push_back(
00101         common::Pow2(rotational_errors_degrees.back()));
00102   }
00103   return "Abs translational error " +
00104          MeanAndStdDevString(translational_errors) +
00105          " m\n"
00106          "Sqr translational error " +
00107          MeanAndStdDevString(squared_translational_errors) +
00108          " m^2\n"
00109          "Abs rotational error " +
00110          MeanAndStdDevString(rotational_errors_degrees) +
00111          " deg\n"
00112          "Sqr rotational error " +
00113          MeanAndStdDevString(squared_rotational_errors_degrees) + " deg^2\n";
00114 }
00115 
00116 void WriteRelationMetricsToFile(const std::vector<Error>& errors,
00117                                 const proto::GroundTruth& ground_truth,
00118                                 const std::string& relation_metrics_filename) {
00119   std::ofstream relation_errors_file;
00120   std::string log_file_path;
00121   LOG(INFO) << "Writing relation metrics to '" + relation_metrics_filename +
00122                    "'...";
00123   relation_errors_file.open(relation_metrics_filename);
00124   relation_errors_file
00125       << "translational_error,squared_translational_error,rotational_"
00126          "errors_degree,squared_rotational_errors_degree,"
00127          "expected_translation_x,expected_translation_y,expected_"
00128          "translation_z,expected_rotation_w,expected_rotation_x,"
00129          "expected_rotation_y,expected_rotation_z,covered_distance\n";
00130   for (int relation_index = 0; relation_index < ground_truth.relation_size();
00131        ++relation_index) {
00132     const Error& error = errors[relation_index];
00133     const proto::Relation& relation = ground_truth.relation(relation_index);
00134     double translational_error = std::sqrt(error.translational_squared);
00135     double squared_translational_error = error.translational_squared;
00136     double rotational_errors_degree =
00137         common::RadToDeg(std::sqrt(error.rotational_squared));
00138     double squared_rotational_errors_degree =
00139         common::Pow2(rotational_errors_degree);
00140     relation_errors_file << translational_error << ","
00141                          << squared_translational_error << ","
00142                          << rotational_errors_degree << ","
00143                          << squared_rotational_errors_degree << ","
00144                          << relation.expected().translation().x() << ","
00145                          << relation.expected().translation().y() << ","
00146                          << relation.expected().translation().z() << ","
00147                          << relation.expected().rotation().w() << ","
00148                          << relation.expected().rotation().x() << ","
00149                          << relation.expected().rotation().y() << ","
00150                          << relation.expected().rotation().z() << ","
00151                          << relation.covered_distance() << "\n";
00152   }
00153   relation_errors_file.close();
00154 }
00155 
00156 transform::Rigid3d LookupTransform(
00157     const transform::TransformInterpolationBuffer&
00158         transform_interpolation_buffer,
00159     const common::Time time) {
00160   const common::Time earliest_time =
00161       transform_interpolation_buffer.earliest_time();
00162   if (transform_interpolation_buffer.Has(time)) {
00163     return transform_interpolation_buffer.Lookup(time);
00164   } else if (time < earliest_time) {
00165     return transform_interpolation_buffer.Lookup(earliest_time);
00166   }
00167   return transform_interpolation_buffer.Lookup(
00168       transform_interpolation_buffer.latest_time());
00169 }
00170 
00171 void Run(const std::string& pose_graph_filename,
00172          const std::string& relations_filename,
00173          const bool read_text_file_with_unix_timestamps,
00174          const bool write_relation_metrics) {
00175   LOG(INFO) << "Reading pose graph from '" << pose_graph_filename << "'...";
00176   mapping::proto::PoseGraph pose_graph =
00177       io::DeserializePoseGraphFromFile(pose_graph_filename);
00178 
00179   const transform::TransformInterpolationBuffer transform_interpolation_buffer(
00180       pose_graph.trajectory(0));
00181 
00182   proto::GroundTruth ground_truth;
00183   if (read_text_file_with_unix_timestamps) {
00184     LOG(INFO) << "Reading relations from '" << relations_filename << "'...";
00185     ground_truth = ReadRelationsTextFile(relations_filename);
00186   } else {
00187     LOG(INFO) << "Reading ground truth from '" << relations_filename << "'...";
00188     std::ifstream ground_truth_stream(relations_filename.c_str(),
00189                                       std::ios::binary);
00190     CHECK(ground_truth.ParseFromIstream(&ground_truth_stream));
00191   }
00192 
00193   std::vector<Error> errors;
00194   for (const auto& relation : ground_truth.relation()) {
00195     const auto pose1 =
00196         LookupTransform(transform_interpolation_buffer,
00197                         common::FromUniversal(relation.timestamp1()));
00198     const auto pose2 =
00199         LookupTransform(transform_interpolation_buffer,
00200                         common::FromUniversal(relation.timestamp2()));
00201     const transform::Rigid3d expected =
00202         transform::ToRigid3(relation.expected());
00203     errors.push_back(ComputeError(pose1, pose2, expected));
00204   }
00205 
00206   const std::string relation_metrics_filename =
00207       pose_graph_filename + ".relation_metrics.csv";
00208   if (write_relation_metrics) {
00209     WriteRelationMetricsToFile(errors, ground_truth, relation_metrics_filename);
00210   }
00211 
00212   LOG(INFO) << "Result:\n" << StatisticsString(errors);
00213 }
00214 
00215 }  // namespace
00216 }  // namespace ground_truth
00217 }  // namespace cartographer
00218 
00219 int main(int argc, char** argv) {
00220   google::InitGoogleLogging(argv[0]);
00221   FLAGS_logtostderr = true;
00222   google::SetUsageMessage(
00223       "\n\n"
00224       "This program computes the relation based metric described in:\n"
00225       "R. Kuemmerle, B. Steder, C. Dornhege, M. Ruhnke, G. Grisetti,\n"
00226       "C. Stachniss, and A. Kleiner, \"On measuring the accuracy of SLAM\n"
00227       "algorithms,\" Autonomous Robots, vol. 27, no. 4, pp. 387–407, 2009.");
00228   google::ParseCommandLineFlags(&argc, &argv, true);
00229 
00230   if (FLAGS_pose_graph_filename.empty() || FLAGS_relations_filename.empty()) {
00231     google::ShowUsageWithFlagsRestrict(argv[0], "compute_relations_metrics");
00232     return EXIT_FAILURE;
00233   }
00234 
00235   ::cartographer::ground_truth::Run(
00236       FLAGS_pose_graph_filename, FLAGS_relations_filename,
00237       FLAGS_read_text_file_with_unix_timestamps, FLAGS_write_relation_metrics);
00238 }


cartographer
Author(s): The Cartographer Authors
autogenerated on Thu May 9 2019 02:27:35