live_align_trajectory.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 <geometry_msgs/PoseStamped.h>
23 #include <nav_msgs/Path.h>
24 #include <ros/ros.h>
25 
27 #include "alignment/AlignUtils.h"
28 #include "utils/Loader.h"
29 #include "utils/colors.h"
30 #include "utils/print.h"
31 #include "utils/quat_ops.h"
32 
34 void align_and_publish(const nav_msgs::Path::ConstPtr &msg);
35 std::vector<double> times_gt;
36 std::vector<Eigen::Matrix<double, 7, 1>> poses_gt;
37 std::string alignment_type;
38 
39 int main(int argc, char **argv) {
40 
41  // Create ros node
42  ros::init(argc, argv, "live_align_trajectory");
43  ros::NodeHandle nh("~");
44 
45  // Verbosity setting
46  std::string verbosity;
47  nh.param<std::string>("verbosity", verbosity, "INFO");
49 
50  // Load what type of alignment we should use
51  nh.param<std::string>("alignment_type", alignment_type, "posyaw");
52 
53  // If we don't have it, or it is empty then error
54  if (!nh.hasParam("path_gt")) {
55  ROS_ERROR("[LOAD]: Please provide a groundtruth file path!!!");
56  std::exit(EXIT_FAILURE);
57  }
58 
59  // Load our groundtruth from file
60  std::string path_to_gt;
61  nh.param<std::string>("path_gt", path_to_gt, "");
62  boost::filesystem::path infolder(path_to_gt);
63  if (infolder.extension() == ".csv") {
64  std::vector<Eigen::Matrix3d> cov_ori_temp, cov_pos_temp;
65  ov_eval::Loader::load_data_csv(path_to_gt, times_gt, poses_gt, cov_ori_temp, cov_pos_temp);
66  } else {
67  std::vector<Eigen::Matrix3d> cov_ori_temp, cov_pos_temp;
68  ov_eval::Loader::load_data(path_to_gt, times_gt, poses_gt, cov_ori_temp, cov_pos_temp);
69  }
70 
71  // Our subscribe and publish nodes
72  ros::Subscriber sub = nh.subscribe("/ov_msckf/pathimu", 1, align_and_publish);
73  pub_path = nh.advertise<nav_msgs::Path>("/ov_msckf/pathgt", 2);
74  ROS_INFO("Subscribing: %s", sub.getTopic().c_str());
75  ROS_INFO("Publishing: %s", pub_path.getTopic().c_str());
76 
77  // Spin
78  ros::spin();
79 }
80 
81 void align_and_publish(const nav_msgs::Path::ConstPtr &msg) {
82 
83  // Convert the message into correct vector format
84  // tx ty tz qx qy qz qw
85  std::vector<double> times_temp;
86  std::vector<Eigen::Matrix<double, 7, 1>> poses_temp;
87  for (auto const &pose : msg->poses) {
88  times_temp.push_back(pose.header.stamp.toSec());
89  Eigen::Matrix<double, 7, 1> pose_tmp;
90  pose_tmp << pose.pose.position.x, pose.pose.position.y, pose.pose.position.z, pose.pose.orientation.x, pose.pose.orientation.y,
91  pose.pose.orientation.z, pose.pose.orientation.w;
92  poses_temp.push_back(pose_tmp);
93  }
94 
95  // Intersect timestamps
96  std::vector<double> gt_times_temp = times_gt;
97  std::vector<Eigen::Matrix<double, 7, 1>> gt_poses_temp = poses_gt;
98  ov_eval::AlignUtils::perform_association(0, 0.02, times_temp, gt_times_temp, poses_temp, gt_poses_temp);
99 
100  // Return failure if we didn't have any common timestamps
101  if (poses_temp.size() < 3) {
102  PRINT_ERROR(RED "[TRAJ]: unable to get enough common timestamps between trajectories.\n" RESET);
103  PRINT_ERROR(RED "[TRAJ]: does the estimated trajectory publish the rosbag timestamps??\n" RESET);
104  return;
105  }
106 
107  // Perform alignment of the trajectories
108  Eigen::Matrix3d R_ESTtoGT;
109  Eigen::Vector3d t_ESTinGT;
110  double s_ESTtoGT;
111  ov_eval::AlignTrajectory::align_trajectory(poses_temp, gt_poses_temp, R_ESTtoGT, t_ESTinGT, s_ESTtoGT, alignment_type);
112  Eigen::Vector4d q_ESTtoGT = ov_core::rot_2_quat(R_ESTtoGT);
113  PRINT_DEBUG("[TRAJ]: q_ESTtoGT = %.3f, %.3f, %.3f, %.3f | p_ESTinGT = %.3f, %.3f, %.3f | s = %.2f\n", q_ESTtoGT(0), q_ESTtoGT(1),
114  q_ESTtoGT(2), q_ESTtoGT(3), t_ESTinGT(0), t_ESTinGT(1), t_ESTinGT(2), s_ESTtoGT);
115 
116  // Finally lets calculate the aligned trajectories
117  // TODO: maybe in the future we could live publish trajectory errors...
118  // NOTE: We downsample the number of poses as needed to prevent rviz crashes
119  // NOTE: https://github.com/ros-visualization/rviz/issues/1107
120  nav_msgs::Path arr_groundtruth;
121  arr_groundtruth.header = msg->header;
122  for (size_t i = 0; i < gt_times_temp.size(); i += std::floor(gt_times_temp.size() / 16384.0) + 1) {
123 
124  // Convert into the correct frame
125  double timestamp = gt_times_temp.at(i);
126  Eigen::Matrix<double, 7, 1> pose_inGT = gt_poses_temp.at(i);
127  Eigen::Vector3d pos_IinEST = R_ESTtoGT.transpose() * (pose_inGT.block(0, 0, 3, 1) - t_ESTinGT) / s_ESTtoGT;
128  Eigen::Vector4d quat_ESTtoI = ov_core::quat_multiply(pose_inGT.block(3, 0, 4, 1), q_ESTtoGT);
129  // Finally push back
130  geometry_msgs::PoseStamped posetemp;
131  posetemp.header = msg->header;
132  posetemp.header.stamp = ros::Time(timestamp);
133  posetemp.pose.orientation.x = quat_ESTtoI(0);
134  posetemp.pose.orientation.y = quat_ESTtoI(1);
135  posetemp.pose.orientation.z = quat_ESTtoI(2);
136  posetemp.pose.orientation.w = quat_ESTtoI(3);
137  posetemp.pose.position.x = pos_IinEST(0);
138  posetemp.pose.position.y = pos_IinEST(1);
139  posetemp.pose.position.z = pos_IinEST(2);
140  arr_groundtruth.poses.push_back(posetemp);
141  }
142  pub_path.publish(arr_groundtruth);
143 }
Eigen::Matrix< double, 4, 1 > quat_multiply(const Eigen::Matrix< double, 4, 1 > &q, const Eigen::Matrix< double, 4, 1 > &p)
std::string getTopic() const
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
std::string alignment_type
#define RESET
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
RED
ros::Publisher pub_path
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void align_and_publish(const nav_msgs::Path::ConstPtr &msg)
std::vector< double > times_gt
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.
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
Eigen::Matrix< double, 4, 1 > rot_2_quat(const Eigen::Matrix< double, 3, 3 > &rot)
#define ROS_INFO(...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static void load_data_csv(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 comma separated trajectory into memory (ASL/ETH format)
Definition: Loader.cpp:109
ROSCPP_DECL void spin()
static void setPrintLevel(const std::string &level)
bool hasParam(const std::string &key) const
std::string getTopic() const
std::vector< Eigen::Matrix< double, 7, 1 > > poses_gt
int main(int argc, char **argv)
#define ROS_ERROR(...)


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