plot_trajectories.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/predicate.hpp>
24 #include <boost/filesystem.hpp>
25 #include <boost/foreach.hpp>
26 #include <fstream>
27 #include <iostream>
28 #include <string>
29 
31 #include "alignment/AlignUtils.h"
32 #include "utils/Loader.h"
33 #include "utils/colors.h"
34 #include "utils/print.h"
35 #include "utils/quat_ops.h"
36 
37 #ifdef HAVE_PYTHONLIBS
38 
39 // import the c++ wrapper for matplot lib
40 // https://github.com/lava/matplotlib-cpp
41 // sudo apt-get install python-matplotlib python-numpy python2.7-dev
42 #include "plot/matplotlibcpp.h"
43 
44 // Will plot the xy 3d position of the pose trajectories
45 void plot_xy_positions(const std::string &name, const std::string &color, const std::vector<Eigen::Matrix<double, 7, 1>> &poses) {
46 
47  // Paramters for our line
48  std::map<std::string, std::string> params;
49  params.insert({"label", name});
50  params.insert({"linestyle", "-"});
51  params.insert({"color", color});
52 
53  // Create vectors of our x and y axis
54  std::vector<double> x, y;
55  for (size_t i = 0; i < poses.size(); i++) {
56  x.push_back(poses.at(i)(0));
57  y.push_back(poses.at(i)(1));
58  }
59 
60  // Finally plot
61  matplotlibcpp::plot(x, y, params);
62 }
63 
64 // Will plot the z 3d position of the pose trajectories
65 void plot_z_positions(const std::string &name, const std::string &color, const std::vector<double> &times,
66  const std::vector<Eigen::Matrix<double, 7, 1>> &poses) {
67 
68  // Paramters for our line
69  std::map<std::string, std::string> params;
70  params.insert({"label", name});
71  params.insert({"linestyle", "-"});
72  params.insert({"color", color});
73 
74  // Create vectors of our x and y axis
75  std::vector<double> time, z;
76  for (size_t i = 0; i < poses.size(); i++) {
77  time.push_back(times.at(i));
78  z.push_back(poses.at(i)(2));
79  }
80 
81  // Finally plot
82  matplotlibcpp::plot(time, z, params);
83 }
84 
85 #endif
86 
87 int main(int argc, char **argv) {
88 
89  // Verbosity setting
91 
92  // Ensure we have a path
93  if (argc < 3) {
94  PRINT_ERROR(RED "ERROR: Please specify a align mode and trajectory file\n" RESET);
95  PRINT_ERROR(RED "ERROR: ./plot_trajectories <align_mode> <file_gt.txt> <file_est1.txt> ... <file_est9.txt>\n" RESET);
96  PRINT_ERROR(RED "ERROR: rosrun ov_eval plot_trajectories <align_mode> <file_gt.txt> <file_est1.txt> ... <file_est9.txt>\n" RESET);
97  std::exit(EXIT_FAILURE);
98  }
99 
100  // Read in all our trajectories from file
101  std::vector<std::string> names;
102  std::vector<std::vector<double>> times;
103  std::vector<std::vector<Eigen::Matrix<double, 7, 1>>> poses;
104  for (int i = 2; i < argc; i++) {
105 
106  // Read in trajectory data
107  std::vector<double> times_temp;
108  std::vector<Eigen::Matrix<double, 7, 1>> poses_temp;
109  std::vector<Eigen::Matrix3d> cov_ori_temp, cov_pos_temp;
110  ov_eval::Loader::load_data(argv[i], times_temp, poses_temp, cov_ori_temp, cov_pos_temp);
111 
112  // Align all the non-groundtruth trajectories to the base one
113  if (i > 2) {
114 
115  // Intersect timestamps
116  std::vector<double> gt_times_temp(times.at(0));
117  std::vector<Eigen::Matrix<double, 7, 1>> gt_poses_temp(poses.at(0));
118  ov_eval::AlignUtils::perform_association(0, 0.02, times_temp, gt_times_temp, poses_temp, gt_poses_temp);
119 
120  // Return failure if we didn't have any common timestamps
121  if (poses_temp.size() < 3) {
122  PRINT_ERROR(RED "[TRAJ]: unable to get enough common timestamps between trajectories.\n" RESET);
123  PRINT_ERROR(RED "[TRAJ]: does the estimated trajectory publish the rosbag timestamps??\n" RESET);
124  std::exit(EXIT_FAILURE);
125  }
126 
127  // Perform alignment of the trajectories
128  Eigen::Matrix3d R_ESTtoGT;
129  Eigen::Vector3d t_ESTinGT;
130  double s_ESTtoGT;
131  ov_eval::AlignTrajectory::align_trajectory(poses_temp, gt_poses_temp, R_ESTtoGT, t_ESTinGT, s_ESTtoGT, argv[1]);
132 
133  // Debug print to the user
134  Eigen::Vector4d q_ESTtoGT = ov_core::rot_2_quat(R_ESTtoGT);
135  PRINT_DEBUG("[TRAJ]: q_ESTtoGT = %.3f, %.3f, %.3f, %.3f | p_ESTinGT = %.3f, %.3f, %.3f | s = %.2f\n", q_ESTtoGT(0), q_ESTtoGT(1),
136  q_ESTtoGT(2), q_ESTtoGT(3), t_ESTinGT(0), t_ESTinGT(1), t_ESTinGT(2), s_ESTtoGT);
137 
138  // Finally lets calculate the aligned trajectories
139  std::vector<Eigen::Matrix<double, 7, 1>> est_poses_aignedtoGT;
140  for (size_t j = 0; j < gt_times_temp.size(); j++) {
141  Eigen::Matrix<double, 7, 1> pose_ESTinGT;
142  pose_ESTinGT.block(0, 0, 3, 1) = s_ESTtoGT * R_ESTtoGT * poses_temp.at(j).block(0, 0, 3, 1) + t_ESTinGT;
143  pose_ESTinGT.block(3, 0, 4, 1) = ov_core::quat_multiply(poses_temp.at(j).block(3, 0, 4, 1), ov_core::Inv(q_ESTtoGT));
144  est_poses_aignedtoGT.push_back(pose_ESTinGT);
145  }
146 
147  // Overwrite our poses with the corrected ones
148  poses_temp = est_poses_aignedtoGT;
149  }
150 
151  // Debug print the length stats
152  boost::filesystem::path path(argv[i]);
153  std::string name = path.stem().string();
154  double length = ov_eval::Loader::get_total_length(poses_temp);
155  PRINT_INFO("[COMP]: %d poses in %s => length of %.2f meters\n", (int)times_temp.size(), name.c_str(), length);
156 
157  // Save this to our arrays
158  names.push_back(name);
159  times.push_back(times_temp);
160  poses.push_back(poses_temp);
161  }
162 
163 #ifdef HAVE_PYTHONLIBS
164 
165  // Colors that we are plotting
166  std::vector<std::string> colors = {"black", "blue", "red", "green", "cyan", "magenta"};
167  // assert(algo_rpe.size() <= colors.size()*linestyle.size());
168 
169  // Plot this figure
170  matplotlibcpp::figure_size(1000, 750);
171 
172  // Plot the position trajectories
173  for (size_t i = 0; i < times.size(); i++) {
174  plot_xy_positions(names.at(i), colors.at(i), poses.at(i));
175  }
176 
177  // Display to the user
178  matplotlibcpp::xlabel("x-axis (m)");
179  matplotlibcpp::ylabel("y-axis (m)");
181  matplotlibcpp::show(false);
182 
183  // Plot this figure
184  matplotlibcpp::figure_size(1000, 350);
185 
186  // Zero our time arrays
187  double starttime = (times.at(0).empty()) ? 0 : times.at(0).at(0);
188  double endtime = (times.at(0).empty()) ? 0 : times.at(0).at(times.at(0).size() - 1);
189  for (size_t i = 0; i < times.size(); i++) {
190  for (size_t j = 0; j < times.at(i).size(); j++) {
191  times.at(i).at(j) -= starttime;
192  }
193  }
194 
195  // Plot the position trajectories
196  for (size_t i = 0; i < times.size(); i++) {
197  plot_z_positions(names.at(i), colors.at(i), times.at(i), poses.at(i));
198  }
199 
200  // Display to the user
201  matplotlibcpp::xlabel("timestamp (sec)");
202  matplotlibcpp::ylabel("z-axis (m)");
203  matplotlibcpp::xlim(0.0, endtime - starttime);
206  matplotlibcpp::show(true);
207 
208 #endif
209 
210  // Done!
211  return EXIT_SUCCESS;
212 }
Eigen::Matrix< double, 4, 1 > quat_multiply(const Eigen::Matrix< double, 4, 1 > &q, const Eigen::Matrix< double, 4, 1 > &p)
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
static void perform_association(double offset, double max_difference, std::vector< double > &est_times, std::vector< double > &gt_times, std::vector< Eigen::Matrix< double, 7, 1 >> &est_poses, std::vector< Eigen::Matrix< double, 7, 1 >> &gt_poses)
Will intersect our loaded data so that we have common timestamps.
Definition: AlignUtils.cpp:95
#define RESET
RED
Eigen::Matrix< double, 4, 1 > Inv(Eigen::Matrix< double, 4, 1 > q)
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
static void align_trajectory(const std::vector< Eigen::Matrix< double, 7, 1 >> &traj_es, const std::vector< Eigen::Matrix< double, 7, 1 >> &traj_gt, Eigen::Matrix3d &R, Eigen::Vector3d &t, double &s, std::string method, int n_aligned=-1)
Align estimate to GT using a desired method using a set of initial poses.
void show(const bool block=true)
int main(int argc, char **argv)
Eigen::Matrix< double, 4, 1 > rot_2_quat(const Eigen::Matrix< double, 3, 3 > &rot)
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 ylabel(const std::string &str, const std::map< std::string, std::string > &keywords={})
void tight_layout()


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