error_dataset.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 <string>
26 
27 #include "calc/ResultTrajectory.h"
28 #include "utils/Loader.h"
29 #include "utils/colors.h"
30 #include "utils/print.h"
31 
32 #ifdef HAVE_PYTHONLIBS
33 
34 // import the c++ wrapper for matplot lib
35 // https://github.com/lava/matplotlib-cpp
36 // sudo apt-get install python-matplotlib python-numpy python2.7-dev
37 #include "plot/matplotlibcpp.h"
38 
39 #endif
40 
41 int main(int argc, char **argv) {
42 
43  // Verbosity setting
45 
46  // Ensure we have a path
47  if (argc < 4) {
48  PRINT_ERROR(RED "ERROR: Please specify a align mode, folder, and algorithms\n" RESET);
49  PRINT_ERROR(RED "ERROR: ./error_dataset <align_mode> <file_gt.txt> <folder_algorithms>\n" RESET);
50  PRINT_ERROR(RED "ERROR: rosrun ov_eval error_dataset <align_mode> <file_gt.txt> <folder_algorithms>\n" RESET);
51  std::exit(EXIT_FAILURE);
52  }
53 
54  // Load it!
55  boost::filesystem::path path_gt(argv[2]);
56  std::vector<double> times;
57  std::vector<Eigen::Matrix<double, 7, 1>> poses;
58  std::vector<Eigen::Matrix3d> cov_ori, cov_pos;
59  ov_eval::Loader::load_data(argv[2], times, poses, cov_ori, cov_pos);
60 
61  // Print its length and stats
62  double length = ov_eval::Loader::get_total_length(poses);
63  PRINT_INFO("[COMP]: %d poses in %s => length of %.2f meters\n", (int)times.size(), path_gt.stem().string().c_str(), length);
64 
65  // Get the algorithms we will process
66  // Also create empty statistic objects for each of our datasets
67  std::string path_algos(argv[3]);
68  std::vector<boost::filesystem::path> path_algorithms;
69  for (const auto &entry : boost::filesystem::directory_iterator(path_algos)) {
70  if (boost::filesystem::is_directory(entry)) {
71  path_algorithms.push_back(entry.path());
72  }
73  }
74  std::sort(path_algorithms.begin(), path_algorithms.end());
75 
76  //===============================================================================
77  //===============================================================================
78  //===============================================================================
79 
80  // ATE summery information
81  std::map<std::string, std::pair<ov_eval::Statistics, ov_eval::Statistics>> algo_ate;
82  std::map<std::string, std::pair<ov_eval::Statistics, ov_eval::Statistics>> algo_nees;
83  for (const auto &p : path_algorithms) {
84  algo_ate.insert({p.filename().string(), {ov_eval::Statistics(), ov_eval::Statistics()}});
85  algo_nees.insert({p.filename().string(), {ov_eval::Statistics(), ov_eval::Statistics()}});
86  }
87 
88  // Relative pose error segment lengths
89  // std::vector<double> segments = {8.0, 16.0, 24.0, 32.0, 40.0, 48.0};
90  std::vector<double> segments = {7.0, 14.0, 21.0, 28.0, 35.0};
91  // std::vector<double> segments = {10.0, 25.0, 50.0, 75.0, 120.0};
92  // std::vector<double> segments = {5.0, 15.0, 30.0, 45.0, 60.0};
93  // std::vector<double> segments = {40.0, 60.0, 80.0, 100.0, 120.0};
94 
95  // The overall RPE error calculation for each algorithm type
96  std::map<std::string, std::map<double, std::pair<ov_eval::Statistics, ov_eval::Statistics>>> algo_rpe;
97  for (const auto &p : path_algorithms) {
98  std::map<double, std::pair<ov_eval::Statistics, ov_eval::Statistics>> temp;
99  for (const auto &len : segments) {
100  temp.insert({len, {ov_eval::Statistics(), ov_eval::Statistics()}});
101  }
102  algo_rpe.insert({p.filename().string(), temp});
103  }
104 
105  //===============================================================================
106  //===============================================================================
107  //===============================================================================
108 
109  // Loop through each algorithm type
110  for (size_t i = 0; i < path_algorithms.size(); i++) {
111 
112  // Debug print
113  PRINT_DEBUG("======================================\n");
114  PRINT_DEBUG("[COMP]: processing %s algorithm\n", path_algorithms.at(i).filename().c_str());
115 
116  // Get the list of datasets this algorithm records
117  std::map<std::string, boost::filesystem::path> path_algo_datasets;
118  for (auto &entry : boost::filesystem::directory_iterator(path_algorithms.at(i))) {
119  if (boost::filesystem::is_directory(entry)) {
120  path_algo_datasets.insert({entry.path().filename().string(), entry.path()});
121  }
122  }
123 
124  // Check if we have runs for our dataset
125  if (path_algo_datasets.find(path_gt.stem().string()) == path_algo_datasets.end()) {
126  PRINT_DEBUG(RED "[COMP]: %s dataset does not have any runs for %s!!!!!\n" RESET, path_algorithms.at(i).filename().c_str(),
127  path_gt.stem().c_str());
128  continue;
129  }
130 
131  // Errors for this specific dataset (i.e. our averages over the total runs)
132  ov_eval::Statistics ate_dataset_ori, ate_dataset_pos;
133  ov_eval::Statistics ate_2d_dataset_ori, ate_2d_dataset_pos;
134  std::map<double, std::pair<ov_eval::Statistics, ov_eval::Statistics>> rpe_dataset;
135  for (const auto &len : segments) {
136  rpe_dataset.insert({len, {ov_eval::Statistics(), ov_eval::Statistics()}});
137  }
138  std::map<double, std::pair<ov_eval::Statistics, ov_eval::Statistics>> rmse_dataset;
139  std::map<double, std::pair<ov_eval::Statistics, ov_eval::Statistics>> rmse_2d_dataset;
140  std::map<double, std::pair<ov_eval::Statistics, ov_eval::Statistics>> nees_dataset;
141 
142  // Loop though the different runs for this dataset
143  std::vector<std::string> file_paths;
144  for (auto &entry : boost::filesystem::directory_iterator(path_algo_datasets.at(path_gt.stem().string()))) {
145  if (entry.path().extension() != ".txt")
146  continue;
147  file_paths.push_back(entry.path().string());
148  }
149  std::sort(file_paths.begin(), file_paths.end());
150 
151  // Check if we have runs
152  if (file_paths.empty()) {
153  PRINT_DEBUG(RED "\tERROR: No runs found for %s, is the folder structure right??\n" RESET, path_algorithms.at(i).filename().c_str());
154  continue;
155  }
156 
157  // Loop though the different runs for this dataset
158  for (auto &path_esttxt : file_paths) {
159 
160  // Create our trajectory object
161  std::string path_gttxt = path_gt.string();
162  ov_eval::ResultTrajectory traj(path_esttxt, path_gttxt, argv[1]);
163 
164  // Calculate ATE error for this dataset
165  ov_eval::Statistics error_ori, error_pos;
166  traj.calculate_ate(error_ori, error_pos);
167  ate_dataset_ori.values.push_back(error_ori.rmse);
168  ate_dataset_pos.values.push_back(error_pos.rmse);
169  for (size_t j = 0; j < error_ori.values.size(); j++) {
170  rmse_dataset[error_ori.timestamps.at(j)].first.values.push_back(error_ori.values.at(j));
171  rmse_dataset[error_pos.timestamps.at(j)].second.values.push_back(error_pos.values.at(j));
172  assert(error_ori.timestamps.at(j) == error_pos.timestamps.at(j));
173  }
174 
175  // Calculate ATE 2D error for this dataset
176  ov_eval::Statistics error_ori_2d, error_pos_2d;
177  traj.calculate_ate_2d(error_ori_2d, error_pos_2d);
178  ate_2d_dataset_ori.values.push_back(error_ori_2d.rmse);
179  ate_2d_dataset_pos.values.push_back(error_pos_2d.rmse);
180  for (size_t j = 0; j < error_ori_2d.values.size(); j++) {
181  rmse_2d_dataset[error_ori_2d.timestamps.at(j)].first.values.push_back(error_ori_2d.values.at(j));
182  rmse_2d_dataset[error_pos_2d.timestamps.at(j)].second.values.push_back(error_pos_2d.values.at(j));
183  assert(error_ori_2d.timestamps.at(j) == error_pos_2d.timestamps.at(j));
184  }
185 
186  // NEES error for this dataset
187  ov_eval::Statistics nees_ori, nees_pos;
188  traj.calculate_nees(nees_ori, nees_pos);
189  for (size_t j = 0; j < nees_ori.values.size(); j++) {
190  nees_dataset[nees_ori.timestamps.at(j)].first.values.push_back(nees_ori.values.at(j));
191  nees_dataset[nees_ori.timestamps.at(j)].second.values.push_back(nees_pos.values.at(j));
192  assert(nees_ori.timestamps.at(j) == nees_pos.timestamps.at(j));
193  }
194 
195  // Calculate RPE error for this dataset
196  std::map<double, std::pair<ov_eval::Statistics, ov_eval::Statistics>> error_rpe;
197  traj.calculate_rpe(segments, error_rpe);
198  for (const auto &elm : error_rpe) {
199  rpe_dataset.at(elm.first).first.values.insert(rpe_dataset.at(elm.first).first.values.end(), elm.second.first.values.begin(),
200  elm.second.first.values.end());
201  rpe_dataset.at(elm.first).first.timestamps.insert(rpe_dataset.at(elm.first).first.timestamps.end(),
202  elm.second.first.timestamps.begin(), elm.second.first.timestamps.end());
203  rpe_dataset.at(elm.first).second.values.insert(rpe_dataset.at(elm.first).second.values.end(), elm.second.second.values.begin(),
204  elm.second.second.values.end());
205  rpe_dataset.at(elm.first).second.timestamps.insert(rpe_dataset.at(elm.first).second.timestamps.end(),
206  elm.second.second.timestamps.begin(), elm.second.second.timestamps.end());
207  }
208  }
209 
210  // Compute our mean ATE score
211  ate_dataset_ori.calculate();
212  ate_dataset_pos.calculate();
213  ate_2d_dataset_ori.calculate();
214  ate_2d_dataset_pos.calculate();
215 
216  // Print stats for this specific dataset
217  std::string prefix = (ate_dataset_ori.mean > 10 || ate_dataset_pos.mean > 10) ? RED : "";
218  PRINT_DEBUG("%s\tATE: mean_ori = %.3f | mean_pos = %.3f (%d runs)\n" RESET, prefix.c_str(), ate_dataset_ori.mean, ate_dataset_pos.mean,
219  (int)ate_dataset_ori.values.size());
220  PRINT_DEBUG("\tATE: std_ori = %.5f | std_pos = %.5f\n", ate_dataset_ori.std, ate_dataset_pos.std);
221  PRINT_DEBUG("\tATE 2D: mean_ori = %.3f | mean_pos = %.3f (%d runs)\n", ate_2d_dataset_ori.mean, ate_2d_dataset_pos.mean,
222  (int)ate_2d_dataset_ori.values.size());
223  PRINT_DEBUG("\tATE 2D: std_ori = %.5f | std_pos = %.5f\n", ate_2d_dataset_ori.std, ate_2d_dataset_pos.std);
224  for (auto &seg : rpe_dataset) {
225  seg.second.first.calculate();
226  seg.second.second.calculate();
227  PRINT_DEBUG("\tRPE: seg %d - mean_ori = %.3f | mean_pos = %.3f (%d samples)\n", (int)seg.first, seg.second.first.mean,
228  seg.second.second.mean, (int)seg.second.second.values.size());
229  // PRINT_DEBUG("RPE: seg %d - std_ori = %.3f | std_pos = %.3f\n",(int)seg.first,seg.second.first.std,seg.second.second.std);
230  }
231 
232  // RMSE: Convert into the right format (only use times where all runs have an error)
233  ov_eval::Statistics rmse_ori, rmse_pos;
234  for (auto &elm : rmse_dataset) {
235  if (elm.second.first.values.size() == file_paths.size()) {
236  elm.second.first.calculate();
237  elm.second.second.calculate();
238  rmse_ori.timestamps.push_back(elm.first);
239  rmse_ori.values.push_back(elm.second.first.rmse);
240  rmse_pos.timestamps.push_back(elm.first);
241  rmse_pos.values.push_back(elm.second.second.rmse);
242  }
243  }
244  rmse_ori.calculate();
245  rmse_pos.calculate();
246  PRINT_DEBUG("\tRMSE: mean_ori = %.3f | mean_pos = %.3f\n", rmse_ori.mean, rmse_pos.mean);
247 
248  // RMSE: Convert into the right format (only use times where all runs have an error)
249  ov_eval::Statistics rmse_2d_ori, rmse_2d_pos;
250  for (auto &elm : rmse_2d_dataset) {
251  if (elm.second.first.values.size() == file_paths.size()) {
252  elm.second.first.calculate();
253  elm.second.second.calculate();
254  rmse_2d_ori.timestamps.push_back(elm.first);
255  rmse_2d_ori.values.push_back(elm.second.first.rmse);
256  rmse_2d_pos.timestamps.push_back(elm.first);
257  rmse_2d_pos.values.push_back(elm.second.second.rmse);
258  }
259  }
260  rmse_2d_ori.calculate();
261  rmse_2d_pos.calculate();
262  PRINT_DEBUG("\tRMSE 2D: mean_ori = %.3f | mean_pos = %.3f\n", rmse_2d_ori.mean, rmse_2d_pos.mean);
263 
264  // NEES: Convert into the right format (only use times where all runs have an error)
265  ov_eval::Statistics nees_ori, nees_pos;
266  for (auto &elm : nees_dataset) {
267  if (elm.second.first.values.size() == file_paths.size()) {
268  elm.second.first.calculate();
269  elm.second.second.calculate();
270  nees_ori.timestamps.push_back(elm.first);
271  nees_ori.values.push_back(elm.second.first.mean);
272  nees_pos.timestamps.push_back(elm.first);
273  nees_pos.values.push_back(elm.second.second.mean);
274  }
275  }
276  nees_ori.calculate();
277  nees_pos.calculate();
278  PRINT_DEBUG("\tNEES: mean_ori = %.3f | mean_pos = %.3f\n", nees_ori.mean, nees_pos.mean);
279 
280 #ifdef HAVE_PYTHONLIBS
281 
282  //=====================================================
283  // RMSE plot at each timestep
284  matplotlibcpp::figure_size(1000, 600);
285 
286  // Zero our time arrays
287  double starttime1 = (rmse_ori.timestamps.empty()) ? 0 : rmse_ori.timestamps.at(0);
288  double endtime1 = (rmse_ori.timestamps.empty()) ? 0 : rmse_ori.timestamps.at(rmse_ori.timestamps.size() - 1);
289  for (size_t j = 0; j < rmse_ori.timestamps.size(); j++) {
290  rmse_ori.timestamps.at(j) -= starttime1;
291  rmse_pos.timestamps.at(j) -= starttime1;
292  }
293 
294  // Update the title and axis labels
295  matplotlibcpp::subplot(2, 1, 1);
296  matplotlibcpp::title("Root Mean Squared Error - " + path_algorithms.at(i).filename().string());
297  matplotlibcpp::ylabel("Error Orientation (deg)");
298  matplotlibcpp::plot(rmse_ori.timestamps, rmse_ori.values);
299  matplotlibcpp::xlim(0.0, endtime1 - starttime1);
300  matplotlibcpp::subplot(2, 1, 2);
301  matplotlibcpp::ylabel("Error Position (m)");
302  matplotlibcpp::xlabel("dataset time (s)");
303  matplotlibcpp::plot(rmse_pos.timestamps, rmse_pos.values);
304  matplotlibcpp::xlim(0.0, endtime1 - starttime1);
305 
306  // Display to the user
308  matplotlibcpp::show(false);
309 
310  //=====================================================
311 
312  if (!nees_ori.values.empty() && !nees_pos.values.empty()) {
313  // NEES plot at each timestep
314  matplotlibcpp::figure_size(1000, 600);
315 
316  // Zero our time arrays
317  double starttime2 = (nees_ori.timestamps.empty()) ? 0 : nees_ori.timestamps.at(0);
318  double endtime2 = (nees_ori.timestamps.empty()) ? 0 : nees_ori.timestamps.at(nees_ori.timestamps.size() - 1);
319  for (size_t j = 0; j < nees_ori.timestamps.size(); j++) {
320  nees_ori.timestamps.at(j) -= starttime2;
321  nees_pos.timestamps.at(j) -= starttime2;
322  }
323 
324  // Update the title and axis labels
325  matplotlibcpp::subplot(2, 1, 1);
326  matplotlibcpp::title("Normalized Estimation Error Squared - " + path_algorithms.at(i).filename().string());
327  matplotlibcpp::ylabel("NEES Orientation");
328  matplotlibcpp::plot(nees_ori.timestamps, nees_ori.values);
329  matplotlibcpp::xlim(0.0, endtime2 - starttime2);
330  matplotlibcpp::subplot(2, 1, 2);
331  matplotlibcpp::ylabel("NEES Position");
332  matplotlibcpp::xlabel("dataset time (s)");
333  matplotlibcpp::plot(nees_pos.timestamps, nees_pos.values);
334  matplotlibcpp::xlim(0.0, endtime2 - starttime2);
335 
336  // Display to the user
338  matplotlibcpp::show(false);
339  }
340 
341 #endif
342 
343  // Update the global ATE error stats
344  std::string algo = path_algorithms.at(i).filename().string();
345  algo_ate.at(algo).first = ate_dataset_ori;
346  algo_ate.at(algo).second = ate_dataset_pos;
347  algo_nees.at(algo).first = nees_ori;
348  algo_nees.at(algo).second = nees_pos;
349 
350  // Update the global RPE error stats
351  for (const auto &elm : rpe_dataset) {
352  algo_rpe.at(algo).at(elm.first).first.values.insert(algo_rpe.at(algo).at(elm.first).first.values.end(),
353  elm.second.first.values.begin(), elm.second.first.values.end());
354  algo_rpe.at(algo).at(elm.first).first.timestamps.insert(algo_rpe.at(algo).at(elm.first).first.timestamps.end(),
355  elm.second.first.timestamps.begin(), elm.second.first.timestamps.end());
356  algo_rpe.at(algo).at(elm.first).second.values.insert(algo_rpe.at(algo).at(elm.first).second.values.end(),
357  elm.second.second.values.begin(), elm.second.second.values.end());
358  algo_rpe.at(algo).at(elm.first).second.timestamps.insert(algo_rpe.at(algo).at(elm.first).second.timestamps.end(),
359  elm.second.second.timestamps.begin(), elm.second.second.timestamps.end());
360  }
361  }
362  PRINT_DEBUG("\n\n");
363 
364  // Finally print the ATE for all the runs
365  PRINT_INFO("============================================\n");
366  PRINT_INFO("ATE AND NEES LATEX TABLE\n");
367  PRINT_INFO("============================================\n");
368  PRINT_INFO(" & \\textbf{ATE (deg/m)} & \\textbf{NEES (deg/m)} \\\\\\hline\n");
369  for (auto &algo : algo_ate) {
370  std::string algoname = algo.first;
371  boost::replace_all(algoname, "_", "\\_");
372  PRINT_INFO(algoname.c_str());
373  // ate
374  auto ate_oripos = algo.second;
375  if (ate_oripos.first.values.empty() || ate_oripos.second.values.empty()) {
376  PRINT_INFO(" & - / -");
377  } else {
378  ate_oripos.first.calculate();
379  ate_oripos.second.calculate();
380  PRINT_INFO(" & %.3f / %.3f", ate_oripos.first.mean, ate_oripos.second.mean);
381  }
382  // nees
383  auto nees_oripos = algo_nees.at(algo.first);
384  if (nees_oripos.first.values.empty() || nees_oripos.second.values.empty()) {
385  PRINT_INFO(" & - / -");
386  } else {
387  nees_oripos.first.calculate();
388  nees_oripos.second.calculate();
389  PRINT_INFO(" & %.3f / %.3f", nees_oripos.first.mean, nees_oripos.second.mean);
390  }
391  PRINT_INFO(" \\\\\n");
392  }
393  PRINT_INFO("============================================\n");
394 
395  // Finally print the RPE for all the runs
396  PRINT_INFO("============================================\n");
397  PRINT_INFO("RPE LATEX TABLE\n");
398  PRINT_INFO("============================================\n");
399  for (const auto &len : segments) {
400  PRINT_INFO(" & \\textbf{%dm}", (int)len);
401  }
402  PRINT_INFO(" \\\\\\hline\n");
403  for (auto &algo : algo_rpe) {
404  std::string algoname = algo.first;
405  boost::replace_all(algoname, "_", "\\_");
406  PRINT_INFO(algoname.c_str());
407  for (auto &seg : algo.second) {
408  seg.second.first.calculate();
409  seg.second.second.calculate();
410  PRINT_INFO(" & %.3f / %.3f", seg.second.first.mean, seg.second.second.mean);
411  }
412  PRINT_INFO(" \\\\\n");
413  }
414  PRINT_INFO("============================================\n");
415 
416 #ifdef HAVE_PYTHONLIBS
417 
418  // Wait till the user kills this node
419  matplotlibcpp::show(true);
420 
421 #endif
422 
423  // Done!
424  return EXIT_SUCCESS;
425 }
Statistics object for a given set scalar time series values.
Definition: Statistics.h:39
int main(int argc, char **argv)
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
void calculate_nees(Statistics &nees_ori, Statistics &nees_pos)
Computes the Normalized Estimation Error Squared (NEES) for this trajectory.
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.
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={})
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.
std::vector< double > timestamps
Timestamp when these values occured at.
Definition: Statistics.h:64


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