30 #include <boost/date_time/posix_time/posix_time.hpp>
31 #include <boost/filesystem.hpp>
33 #if ROS_AVAILABLE == 1
34 #include <nav_msgs/Path.h>
36 #include <sensor_msgs/PointCloud.h>
37 #include <sensor_msgs/PointCloud2.h>
58 static inline double get_best_yaw(
const Eigen::Matrix<double, 3, 3> &C) {
59 double A = C(0, 1) - C(1, 0);
60 double B = C(0, 0) + C(1, 1);
65 void align_posyaw_single(
const Eigen::Vector4d &q_es_0,
const Eigen::Vector3d &p_es_0,
const Eigen::Vector4d &q_gt_0,
66 const Eigen::Vector3d &p_gt_0, Eigen::Matrix3d &R, Eigen::Vector3d &t) {
69 Eigen::Matrix3d C_R = est_rot * g_rot.transpose();
72 t.noalias() = p_gt_0 - R * p_es_0;
76 int main(
int argc,
char **argv) {
79 std::string config_path =
"unset_path_to_config.yaml";
81 config_path = argv[1];
84 #if ROS_AVAILABLE == 1
86 ros::init(argc, argv,
"test_dynamic_init");
87 auto nh = std::make_shared<ros::NodeHandle>(
"~");
88 nh->param<std::string>(
"config_path", config_path, config_path);
91 auto pub_pathimu = nh->advertise<nav_msgs::Path>(
"/ov_msckf/pathimu", 2);
92 PRINT_DEBUG(
"Publishing: %s\n", pub_pathimu.getTopic().c_str());
93 auto pub_pathgt = nh->advertise<nav_msgs::Path>(
"/ov_msckf/pathgt", 2);
94 PRINT_DEBUG(
"Publishing: %s\n", pub_pathgt.getTopic().c_str());
95 auto pub_loop_point = nh->advertise<sensor_msgs::PointCloud>(
"/ov_msckf/loop_feats", 2);
96 PRINT_DEBUG(
"Publishing: %s\n", pub_loop_point.getTopic().c_str());
97 auto pub_points_sim = nh->advertise<sensor_msgs::PointCloud2>(
"/ov_msckf/points_sim", 2);
98 PRINT_DEBUG(
"Publishing: %s\n", pub_points_sim.getTopic().c_str());
102 auto parser = std::make_shared<ov_core::YamlParser>(config_path);
103 #if ROS_AVAILABLE == 1
104 parser->set_node_handler(nh);
108 std::string verbosity =
"INFO";
109 parser->parse_config(
"verbosity", verbosity);
116 if (!parser->successful()) {
118 std::exit(EXIT_FAILURE);
123 auto imu_readings = std::make_shared<std::vector<ov_core::ImuData>>();
125 auto initializer = std::make_shared<DynamicInitializer>(params, tracker->get_feature_database(), imu_readings);
132 double buffer_timecam = -1;
133 std::vector<int> buffer_camids;
134 std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>> buffer_feats;
144 imu_readings->push_back(message_imu);
149 std::vector<int> camids;
150 std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>> feats;
151 bool hascam = sim.
get_next_cam(time_cam, camids, feats);
155 if (buffer_timecam != -1) {
158 tracker->feed_measurement_simulation(buffer_timecam, buffer_camids, buffer_feats);
166 buffer_timecam = time_cam;
167 buffer_camids = camids;
168 buffer_feats = feats;
171 double timestamp = -1;
172 Eigen::MatrixXd covariance;
173 std::vector<std::shared_ptr<ov_type::Type>> order;
174 std::shared_ptr<ov_type::IMU> _imu;
175 std::map<double, std::shared_ptr<ov_type::PoseJPL>> _clones_IMU;
176 std::unordered_map<size_t, std::shared_ptr<ov_type::Landmark>> _features_SLAM;
179 boost::posix_time::ptime rT1 = boost::posix_time::microsec_clock::local_time();
180 bool success = initializer->initialize(timestamp, covariance, order, _imu, _clones_IMU, _features_SLAM);
181 boost::posix_time::ptime rT2 = boost::posix_time::microsec_clock::local_time();
182 double time = (rT2 - rT1).total_microseconds() * 1e-6;
190 Eigen::Matrix<double, 17, 1> gt_imu;
193 Eigen::Matrix3d R_ESTtoGT_imu;
194 Eigen::Vector3d t_ESTinGT_imu;
195 align_posyaw_single(_imu->quat(), _imu->pos(), gt_imu.block(1, 0, 4, 1), gt_imu.block(5, 0, 3, 1), R_ESTtoGT_imu, t_ESTinGT_imu);
197 gt_imu.block(5, 0, 3, 1) = R_ESTtoGT_imu.transpose() * (gt_imu.block(5, 0, 3, 1) - t_ESTinGT_imu);
198 gt_imu.block(8, 0, 3, 1) = R_ESTtoGT_imu.transpose() * gt_imu.block(8, 0, 3, 1);
201 Eigen::Matrix<double, 15, 1> err = Eigen::Matrix<double, 15, 1>::Zero();
203 Eigen::Matrix3d R_GtoI_hat = _imu->Rot();
204 err.block(0, 0, 3, 1) = -
ov_core::log_so3(R_GtoI_gt * R_GtoI_hat.transpose());
205 err.block(3, 0, 3, 1) = gt_imu.block(5, 0, 3, 1) - _imu->pos();
206 err.block(6, 0, 3, 1) = gt_imu.block(8, 0, 3, 1) - _imu->vel();
207 err.block(9, 0, 3, 1) = gt_imu.block(11, 0, 3, 1) - _imu->bias_g();
208 err.block(12, 0, 3, 1) = gt_imu.block(14, 0, 3, 1) - _imu->bias_a();
212 180.0 / M_PI * err(0 + 0), 180.0 / M_PI * err(0 + 1), 180.0 / M_PI * err(0 + 2), gt_imu(1), gt_imu(2), gt_imu(3),
213 gt_imu(4), _imu->quat()(0), _imu->quat()(1), _imu->quat()(2), _imu->quat()(3));
214 PRINT_INFO(
REDPURPLE "e_pos = %.3f,%.3f,%.3f | %.3f,%.3f,%.3f (true) | %.3f,%.3f,%.3f (est)\n" RESET, err(3 + 0), err(3 + 1),
215 err(3 + 2), gt_imu(5), gt_imu(6), gt_imu(7), _imu->pos()(0), _imu->pos()(1), _imu->pos()(2));
216 PRINT_INFO(
REDPURPLE "e_vel = %.3f,%.3f,%.3f | %.3f,%.3f,%.3f (true) | %.3f,%.3f,%.3f (est)\n" RESET, err(6 + 0), err(6 + 1),
217 err(6 + 2), gt_imu(8), gt_imu(9), gt_imu(10), _imu->vel()(0), _imu->vel()(1), _imu->vel()(2));
218 PRINT_INFO(
REDPURPLE "e_bias_g = %.3f,%.3f,%.3f | %.3f,%.3f,%.3f (true) | %.3f,%.3f,%.3f (est)\n" RESET, err(9 + 0), err(9 + 1),
219 err(9 + 2), gt_imu(11), gt_imu(12), gt_imu(13), _imu->bias_g()(0), _imu->bias_g()(1), _imu->bias_g()(2));
220 PRINT_INFO(
REDPURPLE "e_bias_a = %.3f,%.3f,%.3f | %.3f,%.3f,%.3f (true) | %.3f,%.3f,%.3f (est)\n" RESET, err(12 + 0), err(12 + 1),
221 err(12 + 2), gt_imu(14), gt_imu(15), gt_imu(16), _imu->bias_a()(0), _imu->bias_a()(1), _imu->bias_a()(2));
225 Eigen::MatrixXd information = covariance.inverse();
226 double nees_total = (err.transpose() * information * err)(0, 0);
227 double nees_ori = (err.block(0, 0, 3, 1).transpose() * information.block(0, 0, 3, 3) * err.block(0, 0, 3, 1))(0, 0);
228 double nees_pos = (err.block(3, 0, 3, 1).transpose() * information.block(3, 3, 3, 3) * err.block(3, 0, 3, 1))(0, 0);
229 double nees_vel = (err.block(6, 0, 3, 1).transpose() * information.block(6, 6, 3, 3) * err.block(6, 0, 3, 1))(0, 0);
230 double nees_bg = (err.block(9, 0, 3, 1).transpose() * information.block(9, 9, 3, 3) * err.block(9, 0, 3, 1))(0, 0);
231 double nees_ba = (err.block(12, 0, 3, 1).transpose() * information.block(12, 12, 3, 3) * err.block(12, 0, 3, 1))(0, 0);
232 PRINT_INFO(
REDPURPLE "nees total = %.3f | ori = %.3f | pos = %.3f (ideal is 15 and 3)\n" RESET, nees_total, nees_ori, nees_pos);
235 #if ROS_AVAILABLE == 1
238 double oldestpose_time = -1;
239 std::shared_ptr<ov_type::PoseJPL> oldestpose =
nullptr;
240 for (
auto const &_pose : _clones_IMU) {
241 if (oldestpose ==
nullptr || _pose.first < oldestpose_time) {
242 oldestpose_time = _pose.first;
243 oldestpose = _pose.second;
246 assert(oldestpose !=
nullptr);
247 Eigen::Vector4d q_es_0, q_gt_0;
248 Eigen::Vector3d p_es_0, p_gt_0;
249 q_es_0 = oldestpose->quat();
250 p_es_0 = oldestpose->pos();
251 Eigen::Matrix<double, 17, 1> gt_imustate_0;
254 q_gt_0 = gt_imustate_0.block(1, 0, 4, 1);
255 p_gt_0 = gt_imustate_0.block(5, 0, 3, 1);
256 Eigen::Matrix3d R_ESTtoGT;
257 Eigen::Vector3d t_ESTinGT;
261 nav_msgs::Path arrEST, arrGT;
263 arrEST.header.frame_id =
"global";
265 arrGT.header.frame_id =
"global";
266 for (
auto const &_pose : _clones_IMU) {
267 geometry_msgs::PoseStamped poseEST, poseGT;
268 poseEST.header.stamp =
ros::Time(_pose.first);
269 poseEST.header.frame_id =
"global";
270 poseEST.pose.orientation.x = _pose.second->quat()(0, 0);
271 poseEST.pose.orientation.y = _pose.second->quat()(1, 0);
272 poseEST.pose.orientation.z = _pose.second->quat()(2, 0);
273 poseEST.pose.orientation.w = _pose.second->quat()(3, 0);
274 poseEST.pose.position.x = _pose.second->pos()(0, 0);
275 poseEST.pose.position.y = _pose.second->pos()(1, 0);
276 poseEST.pose.position.z = _pose.second->pos()(2, 0);
277 Eigen::Matrix<double, 17, 1> gt_imustate;
281 gt_imustate.block(5, 0, 3, 1) = R_ESTtoGT.transpose() * (gt_imustate.block(5, 0, 3, 1) - t_ESTinGT);
282 poseGT.header.stamp =
ros::Time(_pose.first);
283 poseGT.header.frame_id =
"global";
284 poseGT.pose.orientation.x = gt_imustate(1);
285 poseGT.pose.orientation.y = gt_imustate(2);
286 poseGT.pose.orientation.z = gt_imustate(3);
287 poseGT.pose.orientation.w = gt_imustate(4);
288 poseGT.pose.position.x = gt_imustate(5);
289 poseGT.pose.position.y = gt_imustate(6);
290 poseGT.pose.position.z = gt_imustate(7);
291 arrEST.poses.push_back(poseEST);
292 arrGT.poses.push_back(poseGT);
294 pub_pathimu.publish(arrEST);
295 pub_pathgt.publish(arrGT);
298 sensor_msgs::PointCloud point_cloud;
299 point_cloud.header.frame_id =
"global";
301 for (
auto const &featpair : _features_SLAM) {
302 geometry_msgs::Point32 p;
303 p.x = (float)featpair.second->get_xyz(
false)(0, 0);
304 p.y = (float)featpair.second->get_xyz(
false)(1, 0);
305 p.z = (float)featpair.second->get_xyz(
false)(2, 0);
306 point_cloud.points.push_back(p);
308 pub_loop_point.publish(point_cloud);
311 sensor_msgs::PointCloud2 cloud;
312 cloud.header.frame_id =
"global";
314 cloud.width = _features_SLAM.size();
316 cloud.is_bigendian =
false;
317 cloud.is_dense =
false;
320 modifier.
resize(_features_SLAM.size());
324 for (
auto &featpair : _features_SLAM) {
326 Eigen::Vector3d feat = sim.
get_map().at(featpair.first - 1);
327 feat = R_ESTtoGT.transpose() * (feat - t_ESTinGT);
328 *out_x = (float)feat(0);
330 *out_y = (float)feat(1);
332 *out_z = (float)feat(2);
335 pub_points_sim.publish(cloud);
340 std::cout <<
'\n' <<
"Press a key to continue...";
341 }
while (std::cin.
get() !=
'\n');
347 imu_readings = std::make_shared<std::vector<ov_core::ImuData>>();
349 initializer = std::make_shared<DynamicInitializer>(params, tracker->get_feature_database(), imu_readings);
350 }
else if (timestamp != -1) {