22 #ifndef OV_EVAL_RECORDER_H
23 #define OV_EVAL_RECORDER_H
29 #include <Eigen/Eigen>
30 #include <boost/filesystem.hpp>
32 #include <geometry_msgs/PoseStamped.h>
33 #include <geometry_msgs/PoseWithCovarianceStamped.h>
34 #include <geometry_msgs/TransformStamped.h>
35 #include <nav_msgs/Odometry.h>
57 boost::filesystem::path dir(filename.c_str());
58 if (boost::filesystem::create_directories(dir.parent_path())) {
59 ROS_INFO(
"Created folder path to output file.");
60 ROS_INFO(
"Path: %s", dir.parent_path().c_str());
63 if (boost::filesystem::exists(filename)) {
64 ROS_WARN(
"Output file exists, deleting old file....");
65 boost::filesystem::remove(filename);
70 ROS_ERROR(
"Unable to open output file!!");
72 std::exit(EXIT_FAILURE);
74 outfile <<
"# timestamp(s) tx ty tz qx qy qz qw Pr11 Pr12 Pr13 Pr22 Pr23 Pr33 Pt11 Pt12 Pt13 Pt22 Pt23 Pt33" << std::endl;
78 p_IinG = Eigen::Vector3d::Zero();
79 cov_rot = Eigen::Matrix<double, 3, 3>::Zero();
80 cov_pos = Eigen::Matrix<double, 3, 3>::Zero();
94 q_ItoG << msg->pose.pose.orientation.x, msg->pose.pose.orientation.y, msg->pose.pose.orientation.z, msg->pose.pose.orientation.w;
95 p_IinG << msg->pose.pose.position.x, msg->pose.pose.position.y, msg->pose.pose.position.z;
96 cov_pos << msg->pose.covariance.at(0), msg->pose.covariance.at(1), msg->pose.covariance.at(2), msg->pose.covariance.at(6),
97 msg->pose.covariance.at(7), msg->pose.covariance.at(8), msg->pose.covariance.at(12), msg->pose.covariance.at(13),
98 msg->pose.covariance.at(14);
99 cov_rot << msg->pose.covariance.at(21), msg->pose.covariance.at(22), msg->pose.covariance.at(23), msg->pose.covariance.at(27),
100 msg->pose.covariance.at(28), msg->pose.covariance.at(29), msg->pose.covariance.at(33), msg->pose.covariance.at(34),
101 msg->pose.covariance.at(35);
112 q_ItoG << msg->pose.orientation.x, msg->pose.orientation.y, msg->pose.orientation.z, msg->pose.orientation.w;
113 p_IinG << msg->pose.position.x, msg->pose.position.y, msg->pose.position.z;
127 q_ItoG << msg->pose.pose.orientation.x, msg->pose.pose.orientation.y, msg->pose.pose.orientation.z, msg->pose.pose.orientation.w;
128 p_IinG << msg->pose.pose.position.x, msg->pose.pose.position.y, msg->pose.pose.position.z;
129 cov_pos << msg->pose.covariance.at(0), msg->pose.covariance.at(1), msg->pose.covariance.at(2), msg->pose.covariance.at(6),
130 msg->pose.covariance.at(7), msg->pose.covariance.at(8), msg->pose.covariance.at(12), msg->pose.covariance.at(13),
131 msg->pose.covariance.at(14);
132 cov_rot << msg->pose.covariance.at(21), msg->pose.covariance.at(22), msg->pose.covariance.at(23), msg->pose.covariance.at(27),
133 msg->pose.covariance.at(28), msg->pose.covariance.at(29), msg->pose.covariance.at(33), msg->pose.covariance.at(34),
134 msg->pose.covariance.at(35);
145 q_ItoG << msg->transform.rotation.x, msg->transform.rotation.y, msg->transform.rotation.z, msg->transform.rotation.w;
146 p_IinG << msg->transform.translation.x, msg->transform.translation.y, msg->transform.translation.z;
159 outfile.setf(std::ios::fixed, std::ios::floatfield);
192 #endif // OV_EVAL_RECORDER_H