error_comparison.cpp
Go to the documentation of this file.
1 /*
2  * OpenVINS: An Open Platform for Visual-Inertial Research
3  * Copyright (C) 2018-2023 Patrick Geneva
4  * Copyright (C) 2018-2023 Guoquan Huang
5  * Copyright (C) 2018-2023 OpenVINS Contributors
6  * Copyright (C) 2018-2019 Kevin Eckenhoff
7  *
8  * This program is free software: you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation, either version 3 of the License, or
11  * (at your option) any later version.
12  *
13  * This program is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  * GNU General Public License for more details.
17  *
18  * You should have received a copy of the GNU General Public License
19  * along with this program. If not, see <https://www.gnu.org/licenses/>.
20  */
21 
22 #include <Eigen/Eigen>
23 #include <boost/algorithm/string.hpp>
24 #include <boost/filesystem.hpp>
25 #include <iostream>
26 #include <string>
27 
28 #include "calc/ResultTrajectory.h"
29 #include "utils/Loader.h"
30 #include "utils/colors.h"
31 #include "utils/print.h"
32 
33 #ifdef HAVE_PYTHONLIBS
34 
35 // import the c++ wrapper for matplot lib
36 // https://github.com/lava/matplotlib-cpp
37 // sudo apt-get install python-matplotlib python-numpy python2.7-dev
38 #include "plot/matplotlibcpp.h"
39 
40 #endif
41 
42 int main(int argc, char **argv) {
43 
44  // Verbosity setting
46 
47  // Ensure we have a path
48  if (argc < 4) {
49  PRINT_ERROR(RED "ERROR: Please specify a align mode, folder, and algorithms\n" RESET);
50  PRINT_ERROR(RED "ERROR: ./error_comparison <align_mode> <folder_groundtruth> <folder_algorithms>\n" RESET);
51  PRINT_ERROR(RED "ERROR: rosrun ov_eval error_comparison <align_mode> <folder_groundtruth> <folder_algorithms>\n" RESET);
52  std::exit(EXIT_FAILURE);
53  }
54 
55  // List the groundtruth files in this folder
56  std::string path_gts(argv[2]);
57  std::vector<boost::filesystem::path> path_groundtruths;
58  for (const auto &p : boost::filesystem::recursive_directory_iterator(path_gts)) {
59  if (p.path().extension() == ".txt") {
60  path_groundtruths.push_back(p.path());
61  }
62  }
63  std::sort(path_groundtruths.begin(), path_groundtruths.end());
64 
65  // Try to load our paths
66  for (size_t i = 0; i < path_groundtruths.size(); i++) {
67  // Load it!
68  std::vector<double> times;
69  std::vector<Eigen::Matrix<double, 7, 1>> poses;
70  std::vector<Eigen::Matrix3d> cov_ori, cov_pos;
71  ov_eval::Loader::load_data(path_groundtruths.at(i).string(), times, poses, cov_ori, cov_pos);
72  // Print its length and stats
73  double length = ov_eval::Loader::get_total_length(poses);
74  PRINT_INFO("[COMP]: %d poses in %s => length of %.2f meters\n", (int)times.size(), path_groundtruths.at(i).filename().c_str(), length);
75  }
76 
77  // Get the algorithms we will process
78  // Also create empty statistic objects for each of our datasets
79  std::string path_algos(argv[3]);
80  std::vector<boost::filesystem::path> path_algorithms;
81  for (const auto &entry : boost::filesystem::directory_iterator(path_algos)) {
82  if (boost::filesystem::is_directory(entry)) {
83  path_algorithms.push_back(entry.path());
84  }
85  }
86  std::sort(path_algorithms.begin(), path_algorithms.end());
87 
88  //===============================================================================
89  //===============================================================================
90  //===============================================================================
91 
92  // ATE summery information
93  std::map<std::string, std::vector<std::pair<ov_eval::Statistics, ov_eval::Statistics>>> algo_ate;
94  std::map<std::string, std::vector<std::pair<ov_eval::Statistics, ov_eval::Statistics>>> algo_ate_2d;
95  for (const auto &p : path_algorithms) {
96  std::vector<std::pair<ov_eval::Statistics, ov_eval::Statistics>> temp;
97  for (size_t i = 0; i < path_groundtruths.size(); i++) {
98  temp.push_back({ov_eval::Statistics(), ov_eval::Statistics()});
99  }
100  algo_ate.insert({p.filename().string(), temp});
101  algo_ate_2d.insert({p.filename().string(), temp});
102  }
103 
104  // Relative pose error segment lengths
105  std::vector<double> segments = {8.0, 16.0, 24.0, 32.0, 40.0, 48.0};
106  // std::vector<double> segments = {7.0, 14.0, 21.0, 28.0, 35.0};
107  // std::vector<double> segments = {10.0, 25.0, 50.0, 75.0, 120.0};
108  // std::vector<double> segments = {5.0, 15.0, 30.0, 45.0, 60.0};
109  // std::vector<double> segments = {40.0, 80.0, 120.0, 160.0, 200.0, 240.0};
110 
111  // The overall RPE error calculation for each algorithm type
112  std::map<std::string, std::map<double, std::pair<ov_eval::Statistics, ov_eval::Statistics>>> algo_rpe;
113  for (const auto &p : path_algorithms) {
114  std::map<double, std::pair<ov_eval::Statistics, ov_eval::Statistics>> temp;
115  for (const auto &len : segments) {
116  temp.insert({len, {ov_eval::Statistics(), ov_eval::Statistics()}});
117  }
118  algo_rpe.insert({p.filename().string(), temp});
119  }
120 
121  //===============================================================================
122  //===============================================================================
123  //===============================================================================
124 
125  // Loop through each algorithm type
126  for (size_t i = 0; i < path_algorithms.size(); i++) {
127 
128  // Debug print
129  PRINT_DEBUG("======================================\n");
130  PRINT_DEBUG("[COMP]: processing %s algorithm\n", path_algorithms.at(i).filename().c_str());
131 
132  // Get the list of datasets this algorithm records
133  std::map<std::string, boost::filesystem::path> path_algo_datasets;
134  for (auto &entry : boost::filesystem::directory_iterator(path_algorithms.at(i))) {
135  if (boost::filesystem::is_directory(entry)) {
136  path_algo_datasets.insert({entry.path().filename().string(), entry.path()});
137  }
138  }
139 
140  // Loop through our list of groundtruth datasets, and see if we have it
141  for (size_t j = 0; j < path_groundtruths.size(); j++) {
142 
143  // Check if we have runs for this dataset
144  if (path_algo_datasets.find(path_groundtruths.at(j).stem().string()) == path_algo_datasets.end()) {
145  PRINT_ERROR(RED "[COMP]: %s dataset does not have any runs for %s!!!!!\n" RESET, path_algorithms.at(i).filename().c_str(),
146  path_groundtruths.at(j).stem().c_str());
147  continue;
148  }
149 
150  // Debug print
151  PRINT_DEBUG("[COMP]: processing %s algorithm => %s dataset\n", path_algorithms.at(i).filename().c_str(),
152  path_groundtruths.at(j).stem().c_str());
153 
154  // Errors for this specific dataset (i.e. our averages over the total runs)
155  ov_eval::Statistics ate_dataset_ori, ate_dataset_pos;
156  ov_eval::Statistics ate_2d_dataset_ori, ate_2d_dataset_pos;
157  std::map<double, std::pair<ov_eval::Statistics, ov_eval::Statistics>> rpe_dataset;
158  for (const auto &len : segments) {
159  rpe_dataset.insert({len, {ov_eval::Statistics(), ov_eval::Statistics()}});
160  }
161 
162  // Loop though the different runs for this dataset
163  std::vector<std::string> file_paths;
164  for (auto &entry : boost::filesystem::directory_iterator(path_algo_datasets.at(path_groundtruths.at(j).stem().string()))) {
165  if (entry.path().extension() != ".txt")
166  continue;
167  file_paths.push_back(entry.path().string());
168  }
169  std::sort(file_paths.begin(), file_paths.end());
170 
171  // Now loop through the sorted vector
172  for (auto &path_esttxt : file_paths) {
173  // Our paths
174  std::string dataset = path_groundtruths.at(j).stem().string();
175  std::string path_gttxt = path_groundtruths.at(j).string();
176 
177  // Create our trajectory object
178  ov_eval::ResultTrajectory traj(path_esttxt, path_gttxt, argv[1]);
179 
180  // Calculate ATE error for this dataset
181  ov_eval::Statistics error_ori, error_pos;
182  traj.calculate_ate(error_ori, error_pos);
183  ate_dataset_ori.values.push_back(error_ori.rmse);
184  ate_dataset_pos.values.push_back(error_pos.rmse);
185 
186  // Calculate ATE 2D error for this dataset
187  ov_eval::Statistics error_ori_2d, error_pos_2d;
188  traj.calculate_ate_2d(error_ori_2d, error_pos_2d);
189  ate_2d_dataset_ori.values.push_back(error_ori_2d.rmse);
190  ate_2d_dataset_pos.values.push_back(error_pos_2d.rmse);
191 
192  // Calculate RPE error for this dataset
193  std::map<double, std::pair<ov_eval::Statistics, ov_eval::Statistics>> error_rpe;
194  traj.calculate_rpe(segments, error_rpe);
195  for (const auto &elm : error_rpe) {
196  rpe_dataset.at(elm.first).first.values.insert(rpe_dataset.at(elm.first).first.values.end(), elm.second.first.values.begin(),
197  elm.second.first.values.end());
198  rpe_dataset.at(elm.first).first.timestamps.insert(rpe_dataset.at(elm.first).first.timestamps.end(),
199  elm.second.first.timestamps.begin(), elm.second.first.timestamps.end());
200  rpe_dataset.at(elm.first).second.values.insert(rpe_dataset.at(elm.first).second.values.end(), elm.second.second.values.begin(),
201  elm.second.second.values.end());
202  rpe_dataset.at(elm.first).second.timestamps.insert(rpe_dataset.at(elm.first).second.timestamps.end(),
203  elm.second.second.timestamps.begin(), elm.second.second.timestamps.end());
204  }
205  }
206 
207  // Compute our mean ATE score
208  ate_dataset_ori.calculate();
209  ate_dataset_pos.calculate();
210  ate_2d_dataset_ori.calculate();
211  ate_2d_dataset_pos.calculate();
212 
213  // Print stats for this specific dataset
214  std::string prefix = (ate_dataset_ori.mean > 10 || ate_dataset_pos.mean > 10) ? RED : "";
215  PRINT_DEBUG("%s\tATE: mean_ori = %.3f | mean_pos = %.3f (%d runs)\n" RESET, prefix.c_str(), ate_dataset_ori.mean,
216  ate_dataset_pos.mean, (int)ate_dataset_pos.values.size());
217  PRINT_DEBUG("\tATE: std_ori = %.3f | std_pos = %.3f\n", ate_dataset_ori.std, ate_dataset_pos.std);
218  PRINT_DEBUG("\tATE 2D: mean_ori = %.3f | mean_pos = %.3f (%d runs)\n", ate_2d_dataset_ori.mean, ate_2d_dataset_pos.mean,
219  (int)ate_2d_dataset_ori.values.size());
220  PRINT_DEBUG("\tATE 2D: std_ori = %.5f | std_pos = %.5f\n", ate_2d_dataset_ori.std, ate_2d_dataset_pos.std);
221  for (auto &seg : rpe_dataset) {
222  seg.second.first.calculate();
223  seg.second.second.calculate();
224  // PRINT_DEBUG("\tRPE: seg %d - mean_ori = %.3f | mean_pos = %.3f (%d
225  // samples)\n",(int)seg.first,seg.second.first.mean,seg.second.second.mean,(int)seg.second.second.values.size());
226  PRINT_DEBUG("\tRPE: seg %d - median_ori = %.4f | median_pos = %.4f (%d samples)\n", (int)seg.first, seg.second.first.median,
227  seg.second.second.median, (int)seg.second.second.values.size());
228  // PRINT_DEBUG("RPE: seg %d - std_ori = %.3f | std_pos = %.3f\n",(int)seg.first,seg.second.first.std,seg.second.second.std);
229  }
230 
231  // Update the global ATE error stats
232  std::string algo = path_algorithms.at(i).filename().string();
233  algo_ate.at(algo).at(j).first = ate_dataset_ori;
234  algo_ate.at(algo).at(j).second = ate_dataset_pos;
235  algo_ate_2d.at(algo).at(j).first = ate_2d_dataset_ori;
236  algo_ate_2d.at(algo).at(j).second = ate_2d_dataset_pos;
237 
238  // Update the global RPE error stats
239  for (const auto &elm : rpe_dataset) {
240  algo_rpe.at(algo).at(elm.first).first.values.insert(algo_rpe.at(algo).at(elm.first).first.values.end(),
241  elm.second.first.values.begin(), elm.second.first.values.end());
242  algo_rpe.at(algo).at(elm.first).first.timestamps.insert(algo_rpe.at(algo).at(elm.first).first.timestamps.end(),
243  elm.second.first.timestamps.begin(), elm.second.first.timestamps.end());
244  algo_rpe.at(algo).at(elm.first).second.values.insert(algo_rpe.at(algo).at(elm.first).second.values.end(),
245  elm.second.second.values.begin(), elm.second.second.values.end());
246  algo_rpe.at(algo).at(elm.first).second.timestamps.insert(algo_rpe.at(algo).at(elm.first).second.timestamps.end(),
247  elm.second.second.timestamps.begin(), elm.second.second.timestamps.end());
248  }
249  }
250  }
251  PRINT_DEBUG("\n\n");
252 
253  //===============================================================================
254  //===============================================================================
255  //===============================================================================
256 
257  // Finally print the ATE for all the runs
258  PRINT_INFO("============================================\n");
259  PRINT_INFO("ATE LATEX TABLE\n");
260  PRINT_INFO("============================================\n");
261  for (size_t i = 0; i < path_groundtruths.size(); i++) {
262  std::string gtname = path_groundtruths.at(i).stem().string();
263  boost::replace_all(gtname, "_", "\\_");
264  PRINT_INFO(" & \\textbf{%s}", gtname.c_str());
265  }
266  PRINT_INFO(" & \\textbf{Average} \\\\\\hline\n");
267  for (auto &algo : algo_ate) {
268  std::string algoname = algo.first;
269  boost::replace_all(algoname, "_", "\\_");
270  PRINT_INFO(algoname.c_str());
271  double sum_ori = 0.0;
272  double sum_pos = 0.0;
273  int sum_ct = 0;
274  for (auto &seg : algo.second) {
275  if (seg.first.values.empty() || seg.second.values.empty()) {
276  PRINT_INFO(" & - / -");
277  } else {
278  seg.first.calculate();
279  seg.second.calculate();
280  PRINT_INFO(" & %.3f / %.3f", seg.first.mean, seg.second.mean);
281  sum_ori += seg.first.mean;
282  sum_pos += seg.second.mean;
283  sum_ct++;
284  }
285  }
286  PRINT_INFO(" & %.3f / %.3f \\\\\n", sum_ori / sum_ct, sum_pos / sum_ct);
287  }
288  PRINT_INFO("============================================\n");
289 
290  // Finally print the ATE for all the runs
291  PRINT_INFO("============================================\n");
292  PRINT_INFO("ATE 2D LATEX TABLE\n");
293  PRINT_INFO("============================================\n");
294  for (size_t i = 0; i < path_groundtruths.size(); i++) {
295  std::string gtname = path_groundtruths.at(i).stem().string();
296  boost::replace_all(gtname, "_", "\\_");
297  PRINT_INFO(" & \\textbf{%s}", gtname.c_str());
298  }
299  PRINT_INFO(" & \\textbf{Average} \\\\\\hline\n");
300  for (auto &algo : algo_ate_2d) {
301  std::string algoname = algo.first;
302  boost::replace_all(algoname, "_", "\\_");
303  PRINT_INFO(algoname.c_str());
304  double sum_ori = 0.0;
305  double sum_pos = 0.0;
306  int sum_ct = 0;
307  for (auto &seg : algo.second) {
308  if (seg.first.values.empty() || seg.second.values.empty()) {
309  PRINT_INFO(" & - / -");
310  } else {
311  seg.first.calculate();
312  seg.second.calculate();
313  PRINT_INFO(" & %.3f / %.3f", seg.first.mean, seg.second.mean);
314  sum_ori += seg.first.mean;
315  sum_pos += seg.second.mean;
316  sum_ct++;
317  }
318  }
319  PRINT_INFO(" & %.3f / %.3f \\\\\n", sum_ori / sum_ct, sum_pos / sum_ct);
320  }
321  PRINT_INFO("============================================\n");
322 
323  // Finally print the RPE for all the runs
324  PRINT_INFO("============================================\n");
325  PRINT_INFO("RPE LATEX TABLE\n");
326  PRINT_INFO("============================================\n");
327  for (const auto &len : segments) {
328  PRINT_INFO(" & \\textbf{%dm}", (int)len);
329  }
330  PRINT_INFO(" \\\\\\hline\n");
331  for (auto &algo : algo_rpe) {
332  std::string algoname = algo.first;
333  boost::replace_all(algoname, "_", "\\_");
334  PRINT_INFO(algoname.c_str());
335  for (auto &seg : algo.second) {
336  seg.second.first.calculate();
337  seg.second.second.calculate();
338  PRINT_INFO(" & %.3f / %.3f", seg.second.first.mean, seg.second.second.mean);
339  }
340  PRINT_INFO(" \\\\\n");
341  }
342  PRINT_INFO("============================================\n");
343 
344 #ifdef HAVE_PYTHONLIBS
345 
346  // Plot line colors
347  std::vector<std::string> colors = {"blue", "red", "black", "green", "cyan", "magenta"};
348  std::vector<std::string> linestyle = {"-", "--", "-."};
349  assert(algo_rpe.size() <= colors.size() * linestyle.size());
350 
351  // Parameters
352  std::map<std::string, std::string> params_rpe;
353  params_rpe.insert({"notch", "false"});
354  params_rpe.insert({"sym", ""});
355 
356  // Plot this figure
357  matplotlibcpp::figure_size(1000, 700);
358  matplotlibcpp::subplot(2, 1, 1);
359  matplotlibcpp::title("Relative Orientation Error");
360 
361  // Plot each RPE next to each other
362  double width = 1.0 / (algo_rpe.size() + 1);
363  double spacing = width / (algo_rpe.size() + 1);
364  std::vector<double> xticks;
365  std::vector<std::string> labels;
366  int ct_algo = 0;
367  double ct_pos = 0;
368  for (auto &algo : algo_rpe) {
369  // Start based on what algorithm we are doing
370  xticks.clear();
371  labels.clear();
372  ct_pos = 1 + ct_algo * (width + spacing);
373  // Loop through each length type
374  for (auto &seg : algo.second) {
375  xticks.push_back(ct_pos - (algo_rpe.size() * (width + spacing) - width) / 2);
376  labels.push_back(std::to_string((int)seg.first));
377  matplotlibcpp::boxplot(seg.second.first.values, ct_pos, width, colors.at(ct_algo % colors.size()),
378  linestyle.at(ct_algo / colors.size()), params_rpe);
379  ct_pos += 1 + 3 * width;
380  }
381  // Move forward
382  ct_algo++;
383  }
384 
385  // Add "fake" plots for our legend
386  ct_algo = 0;
387  for (const auto &algo : algo_rpe) {
388  std::map<std::string, std::string> params_empty;
389  params_empty.insert({"label", algo.first});
390  params_empty.insert({"linestyle", linestyle.at(ct_algo / colors.size())});
391  params_empty.insert({"color", colors.at(ct_algo % colors.size())});
392  std::vector<double> vec_empty;
393  matplotlibcpp::plot(vec_empty, vec_empty, params_empty);
394  ct_algo++;
395  }
396 
397  // Plot each RPE next to each other
398  matplotlibcpp::xlim(0.5, ct_pos - 0.5 - 3 * width);
399  matplotlibcpp::xticks(xticks, labels);
400  matplotlibcpp::ylabel("orientation error (deg)");
402  matplotlibcpp::subplot(2, 1, 2);
403  ct_algo = 0;
404  ct_pos = 0;
405  for (auto &algo : algo_rpe) {
406  // Start based on what algorithm we are doing
407  ct_pos = 1 + ct_algo * (width + spacing);
408  // Loop through each length type
409  for (auto &seg : algo.second) {
410  matplotlibcpp::boxplot(seg.second.second.values, ct_pos, width, colors.at(ct_algo % colors.size()),
411  linestyle.at(ct_algo / colors.size()), params_rpe);
412  ct_pos += 1 + 3 * width;
413  }
414  // Move forward
415  ct_algo++;
416  }
417 
418  // Add "fake" plots for our legend
419  ct_algo = 0;
420  for (const auto &algo : algo_rpe) {
421  std::map<std::string, std::string> params_empty;
422  params_empty.insert({"label", algo.first});
423  params_empty.insert({"linestyle", linestyle.at(ct_algo / colors.size())});
424  params_empty.insert({"color", colors.at(ct_algo % colors.size())});
425  std::vector<double> vec_empty;
426  matplotlibcpp::plot(vec_empty, vec_empty, params_empty);
427  ct_algo++;
428  }
429 
430  // Display to the user
431  matplotlibcpp::xlim(0.5, ct_pos - 0.5 - 3 * width);
432  matplotlibcpp::xticks(xticks, labels);
433  matplotlibcpp::title("Relative Position Error");
434  matplotlibcpp::ylabel("translational error (m)");
435  matplotlibcpp::xlabel("sub-segment lengths (m)");
437  matplotlibcpp::show(true);
438 
439 #endif
440 
441  // Done!
442  return EXIT_SUCCESS;
443 }
Statistics object for a given set scalar time series values.
Definition: Statistics.h:39
void xticks(const std::vector< Numeric > &ticks, const std::vector< std::string > &labels={}, const std::map< std::string, std::string > &keywords={})
static void load_data(std::string path_traj, std::vector< double > &times, std::vector< Eigen::Matrix< double, 7, 1 >> &poses, std::vector< Eigen::Matrix3d > &cov_ori, std::vector< Eigen::Matrix3d > &cov_pos)
This will load space separated trajectory into memory.
Definition: Loader.cpp:26
double rmse
Root mean squared for the given values.
Definition: Statistics.h:43
#define RESET
RED
double mean
Mean of the given values.
Definition: Statistics.h:46
std::vector< double > values
Values (e.g. error or nees at a given time)
Definition: Statistics.h:67
void figure_size(size_t w, size_t h)
bool plot(const std::vector< Numeric > &x, const std::vector< Numeric > &y, const std::map< std::string, std::string > &keywords)
static double get_total_length(const std::vector< Eigen::Matrix< double, 7, 1 >> &poses)
Will calculate the total trajectory distance.
Definition: Loader.cpp:388
void calculate()
Will calculate all values from our vectors of information.
Definition: Statistics.h:73
void show(const bool block=true)
void calculate_ate(Statistics &error_ori, Statistics &error_pos)
Computes the Absolute Trajectory Error (ATE) for this trajectory.
int main(int argc, char **argv)
double std
Standard deviation of given values.
Definition: Statistics.h:52
A single run for a given dataset.
void calculate_ate_2d(Statistics &error_ori, Statistics &error_pos)
Computes the Absolute Trajectory Error (ATE) for this trajectory in the 2d x-y plane.
static void setPrintLevel(const std::string &level)
void xlim(Numeric left, Numeric right)
void xlabel(const std::string &str, const std::map< std::string, std::string > &keywords={})
void subplot(long nrows, long ncols, long plot_number)
void title(const std::string &titlestr, const std::map< std::string, std::string > &keywords={})
void ylabel(const std::string &str, const std::map< std::string, std::string > &keywords={})
bool boxplot(const std::vector< NumericX > &x, const double &position, const double &width, const std::string &color, const std::string &linestyle, const std::map< std::string, std::string > &keywords={}, bool vert=true)
void tight_layout()
void calculate_rpe(const std::vector< double > &segment_lengths, std::map< double, std::pair< Statistics, Statistics >> &error_rpe)
Computes the Relative Pose Error (RPE) for this trajectory.


ov_eval
Author(s): Patrick Geneva , Kevin Eckenhoff , Guoquan Huang
autogenerated on Wed Jun 21 2023 03:05:40