22 #include <geometry_msgs/PoseStamped.h> 23 #include <nav_msgs/Path.h> 36 std::vector<Eigen::Matrix<double, 7, 1>>
poses_gt;
39 int main(
int argc,
char **argv) {
42 ros::init(argc, argv,
"live_align_trajectory");
46 std::string verbosity;
47 nh.
param<std::string>(
"verbosity", verbosity,
"INFO");
55 ROS_ERROR(
"[LOAD]: Please provide a groundtruth file path!!!");
56 std::exit(EXIT_FAILURE);
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;
67 std::vector<Eigen::Matrix3d> cov_ori_temp, cov_pos_temp;
73 pub_path = nh.
advertise<nav_msgs::Path>(
"/ov_msckf/pathgt", 2);
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);
96 std::vector<double> gt_times_temp =
times_gt;
97 std::vector<Eigen::Matrix<double, 7, 1>> gt_poses_temp =
poses_gt;
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);
108 Eigen::Matrix3d R_ESTtoGT;
109 Eigen::Vector3d t_ESTinGT;
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);
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) {
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;
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);
142 pub_path.
publish(arr_groundtruth);
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 > ×, 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.
static void perform_association(double offset, double max_difference, std::vector< double > &est_times, std::vector< double > >_times, std::vector< Eigen::Matrix< double, 7, 1 >> &est_poses, std::vector< Eigen::Matrix< double, 7, 1 >> >_poses)
Will intersect our loaded data so that we have common timestamps.
std::string alignment_type
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
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 ¶m_name, T ¶m_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)
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 > ×, 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)
static void setPrintLevel(const std::string &level)
#define PRINT_ERROR(x...)
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 PRINT_DEBUG(x...)