30 #include <ceres/ceres.h>
32 #include <boost/date_time/posix_time/posix_time.hpp>
33 #include <boost/filesystem.hpp>
35 #if ROS_AVAILABLE == 1
36 #include <nav_msgs/Path.h>
38 #include <sensor_msgs/PointCloud.h>
39 #include <sensor_msgs/PointCloud2.h>
62 int main(
int argc,
char **argv) {
65 std::string config_path =
"unset_path_to_config.yaml";
67 config_path = argv[1];
70 #if ROS_AVAILABLE == 1
72 ros::init(argc, argv,
"test_dynamic_mle");
73 auto nh = std::make_shared<ros::NodeHandle>(
"~");
74 nh->param<std::string>(
"config_path", config_path, config_path);
77 auto pub_pathimu = nh->advertise<nav_msgs::Path>(
"/ov_msckf/pathimu", 2);
78 PRINT_DEBUG(
"Publishing: %s\n", pub_pathimu.getTopic().c_str());
79 auto pub_pathgt = nh->advertise<nav_msgs::Path>(
"/ov_msckf/pathgt", 2);
80 PRINT_DEBUG(
"Publishing: %s\n", pub_pathgt.getTopic().c_str());
81 auto pub_loop_point = nh->advertise<sensor_msgs::PointCloud>(
"/ov_msckf/loop_feats", 2);
82 PRINT_DEBUG(
"Publishing: %s\n", pub_loop_point.getTopic().c_str());
83 auto pub_points_sim = nh->advertise<sensor_msgs::PointCloud2>(
"/ov_msckf/points_sim", 2);
84 PRINT_DEBUG(
"Publishing: %s\n", pub_points_sim.getTopic().c_str());
88 auto parser = std::make_shared<ov_core::YamlParser>(config_path);
89 #if ROS_AVAILABLE == 1
90 parser->set_node_handler(nh);
94 std::string verbosity =
"INFO";
95 parser->parse_config(
"verbosity", verbosity);
102 if (!parser->successful()) {
104 std::exit(EXIT_FAILURE);
114 ceres::Problem problem;
117 std::map<double, int> map_states;
118 std::vector<double *> ceres_vars_ori;
119 std::vector<double *> ceres_vars_pos;
120 std::vector<double *> ceres_vars_vel;
121 std::vector<double *> ceres_vars_bias_g;
122 std::vector<double *> ceres_vars_bias_a;
125 std::map<size_t, int> map_features;
126 std::vector<double *> ceres_vars_feat;
127 typedef std::vector<std::pair<Factor_ImageReprojCalib *, std::vector<double *>>> factpair;
128 std::map<size_t, factpair> map_features_delayed;
131 std::map<size_t, int> map_calib_cam2imu;
132 std::vector<double *> ceres_vars_calib_cam2imu_ori;
133 std::vector<double *> ceres_vars_calib_cam2imu_pos;
136 std::map<size_t, int> map_calib_cam;
137 std::vector<double *> ceres_vars_calib_cam_intrinsics;
142 ceres::Solver::Options options;
143 options.linear_solver_type = ceres::DENSE_SCHUR;
144 options.trust_region_strategy_type = ceres::DOGLEG;
147 options.num_threads = 6;
148 options.max_solver_time_in_seconds = 9999;
149 options.max_num_iterations = 20;
150 options.minimizer_progress_to_stdout =
true;
168 double feat_noise = 0.05;
171 double buffer_timecam = -1;
172 double buffer_timecam_last = -1;
173 std::vector<int> buffer_camids;
174 std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>> buffer_feats;
175 auto imu_readings = std::make_shared<std::vector<ov_core::ImuData>>();
185 imu_readings->push_back(message_imu);
190 std::vector<int> camids;
191 std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>> feats;
192 bool hascam = sim.
get_next_cam(time_cam, camids, feats);
194 if (buffer_timecam != -1) {
197 double timestamp_k = buffer_timecam_last;
198 double timestamp_k1 = buffer_timecam;
199 Eigen::Matrix<double, 16, 1> state_k1;
200 std::shared_ptr<ov_core::CpiV1> cpi =
nullptr;
201 if (map_states.empty()) {
206 Eigen::Matrix<double, 17, 1> gt_imustate;
207 bool success = sim.
get_state(time1, gt_imustate);
209 state_k1 = gt_imustate.block(1, 0, 16, 1);
214 assert(timestamp_k != -1);
215 Eigen::Vector4d quat_k;
216 for (
int i = 0; i < 4; i++) {
217 quat_k(i) = ceres_vars_ori.at(map_states.at(timestamp_k))[i];
219 Eigen::Vector3d pos_k, vel_k, bias_g_k, bias_a_k;
220 for (
int i = 0; i < 3; i++) {
221 pos_k(i) = ceres_vars_pos.at(map_states.at(timestamp_k))[i];
222 vel_k(i) = ceres_vars_vel.at(map_states.at(timestamp_k))[i];
223 bias_g_k(i) = ceres_vars_bias_g.at(map_states.at(timestamp_k))[i];
224 bias_a_k(i) = ceres_vars_bias_a.at(map_states.at(timestamp_k))[i];
226 Eigen::Vector3d gravity;
236 cpi->setLinearizationPoints(bias_g_k, bias_a_k, quat_k, gravity);
237 for (
size_t k = 0; k < readings.size() - 1; k++) {
238 auto imu0 = readings.at(k);
239 auto imu1 = readings.at(k + 1);
240 cpi->feed_IMU(imu0.timestamp, imu1.timestamp, imu0.wm, imu0.am, imu1.wm, imu1.am);
242 assert(timestamp_k1 > timestamp_k);
246 state_k1.block(4, 0, 3, 1) =
247 pos_k + vel_k * cpi->DT - 0.5 * cpi->grav * std::pow(cpi->DT, 2) +
ov_core::quat_2_Rot(quat_k).transpose() * cpi->alpha_tau;
248 state_k1.block(7, 0, 3, 1) = vel_k - cpi->grav * cpi->DT +
ov_core::quat_2_Rot(quat_k).transpose() * cpi->beta_tau;
249 state_k1.block(10, 0, 3, 1) = bias_g_k;
250 state_k1.block(13, 0, 3, 1) = bias_a_k;
258 auto *var_ori =
new double[4];
259 for (
int i = 0; i < 4; i++) {
260 var_ori[i] = state_k1(0 + i, 0);
262 auto *var_pos =
new double[3];
263 auto *var_vel =
new double[3];
264 auto *var_bias_g =
new double[3];
265 auto *var_bias_a =
new double[3];
266 for (
int i = 0; i < 3; i++) {
267 var_pos[i] = state_k1(4 + i, 0);
268 var_vel[i] = state_k1(7 + i, 0);
269 var_bias_g[i] = state_k1(10 + i, 0);
270 var_bias_a[i] = state_k1(13 + i, 0);
275 problem.AddParameterBlock(var_ori, 4, ceres_jplquat);
276 problem.AddParameterBlock(var_pos, 3);
277 problem.AddParameterBlock(var_vel, 3);
278 problem.AddParameterBlock(var_bias_g, 3);
279 problem.AddParameterBlock(var_bias_a, 3);
285 if (map_states.empty()) {
288 Eigen::MatrixXd x_lin = Eigen::MatrixXd::Zero(7, 1);
289 for (
int i = 0; i < 4; i++) {
290 x_lin(0 + i) = var_ori[i];
292 for (
int i = 0; i < 3; i++) {
293 x_lin(4 + i) = var_pos[i];
297 Eigen::MatrixXd prior_grad = Eigen::MatrixXd::Zero(4, 1);
298 Eigen::MatrixXd prior_Info = Eigen::MatrixXd::Identity(4, 4);
299 prior_Info.block(0, 0, 4, 4) *= 1.0 / std::pow(1e-8, 2);
304 std::vector<std::string> x_types;
305 std::vector<double *> factor_params;
306 factor_params.push_back(var_ori);
307 x_types.emplace_back(
"quat_yaw");
308 factor_params.push_back(var_pos);
309 x_types.emplace_back(
"vec3");
317 problem.AddResidualBlock(factor_prior,
nullptr, factor_params);
323 map_states.insert({timestamp_k1, (int)ceres_vars_ori.size()});
324 ceres_vars_ori.push_back(var_ori);
325 ceres_vars_pos.push_back(var_pos);
326 ceres_vars_vel.push_back(var_vel);
327 ceres_vars_bias_g.push_back(var_bias_g);
328 ceres_vars_bias_a.push_back(var_bias_a);
329 buffer_timecam_last = timestamp_k1;
336 if (cpi !=
nullptr) {
337 assert(timestamp_k != -1);
338 std::vector<double *> factor_params;
339 factor_params.push_back(ceres_vars_ori.at(map_states.at(timestamp_k)));
340 factor_params.push_back(ceres_vars_bias_g.at(map_states.at(timestamp_k)));
341 factor_params.push_back(ceres_vars_vel.at(map_states.at(timestamp_k)));
342 factor_params.push_back(ceres_vars_bias_a.at(map_states.at(timestamp_k)));
343 factor_params.push_back(ceres_vars_pos.at(map_states.at(timestamp_k)));
344 factor_params.push_back(ceres_vars_ori.at(map_states.at(timestamp_k1)));
345 factor_params.push_back(ceres_vars_bias_g.at(map_states.at(timestamp_k1)));
346 factor_params.push_back(ceres_vars_vel.at(map_states.at(timestamp_k1)));
347 factor_params.push_back(ceres_vars_bias_a.at(map_states.at(timestamp_k1)));
348 factor_params.push_back(ceres_vars_pos.at(map_states.at(timestamp_k1)));
349 auto *factor_imu =
new Factor_ImuCPIv1(cpi->DT, cpi->grav, cpi->alpha_tau, cpi->beta_tau, cpi->q_k2tau, cpi->b_a_lin,
350 cpi->b_w_lin, cpi->J_q, cpi->J_b, cpi->J_a, cpi->H_b, cpi->H_a, cpi->P_meas);
351 problem.AddResidualBlock(factor_imu,
nullptr, factor_params);
356 assert(buffer_camids.size() == buffer_feats.size());
357 for (
size_t n = 0; n < buffer_camids.size(); n++) {
360 int cam_id = buffer_camids.at(n);
361 if (map_calib_cam2imu.find(cam_id) == map_calib_cam2imu.end()) {
362 auto *var_calib_ori =
new double[4];
363 for (
int i = 0; i < 4; i++) {
366 auto *var_calib_pos =
new double[3];
367 for (
int i = 0; i < 3; i++) {
371 problem.AddParameterBlock(var_calib_ori, 4, ceres_calib_jplquat);
372 problem.AddParameterBlock(var_calib_pos, 3);
373 map_calib_cam2imu.insert({cam_id, (int)ceres_vars_calib_cam2imu_ori.size()});
374 ceres_vars_calib_cam2imu_ori.push_back(var_calib_ori);
375 ceres_vars_calib_cam2imu_pos.push_back(var_calib_pos);
378 Eigen::MatrixXd x_lin = Eigen::MatrixXd::Zero(7, 1);
379 for (
int i = 0; i < 4; i++) {
380 x_lin(0 + i) = var_calib_ori[i];
382 for (
int i = 0; i < 3; i++) {
383 x_lin(4 + i) = var_calib_pos[i];
385 Eigen::MatrixXd prior_grad = Eigen::MatrixXd::Zero(6, 1);
386 Eigen::MatrixXd prior_Info = Eigen::MatrixXd::Identity(6, 6);
387 prior_Info.block(0, 0, 3, 3) *= 1.0 / std::pow(0.001, 2);
388 prior_Info.block(3, 3, 3, 3) *= 1.0 / std::pow(0.01, 2);
391 std::vector<std::string> x_types;
392 std::vector<double *> factor_params;
393 factor_params.push_back(var_calib_ori);
394 x_types.emplace_back(
"quat");
395 factor_params.push_back(var_calib_pos);
396 x_types.emplace_back(
"vec3");
398 problem.SetParameterBlockConstant(var_calib_ori);
399 problem.SetParameterBlockConstant(var_calib_pos);
402 problem.AddResidualBlock(factor_prior,
nullptr, factor_params);
405 bool is_fisheye = (std::dynamic_pointer_cast<ov_core::CamEqui>(params.
camera_intrinsics.at(cam_id)) !=
nullptr);
406 if (map_calib_cam.find(cam_id) == map_calib_cam.end()) {
407 auto *var_calib_cam =
new double[8];
408 for (
int i = 0; i < 8; i++) {
411 problem.AddParameterBlock(var_calib_cam, 8);
412 map_calib_cam.insert({cam_id, (int)ceres_vars_calib_cam_intrinsics.size()});
413 ceres_vars_calib_cam_intrinsics.push_back(var_calib_cam);
416 Eigen::MatrixXd x_lin = Eigen::MatrixXd::Zero(8, 1);
417 for (
int i = 0; i < 8; i++) {
418 x_lin(0 + i) = var_calib_cam[i];
420 Eigen::MatrixXd prior_grad = Eigen::MatrixXd::Zero(8, 1);
421 Eigen::MatrixXd prior_Info = Eigen::MatrixXd::Identity(8, 8);
422 prior_Info.block(0, 0, 4, 4) *= 1.0 / std::pow(1.0, 2);
423 prior_Info.block(4, 4, 4, 4) *= 1.0 / std::pow(0.005, 2);
426 std::vector<std::string> x_types;
427 std::vector<double *> factor_params;
428 factor_params.push_back(var_calib_cam);
429 x_types.emplace_back(
"vec8");
431 problem.SetParameterBlockConstant(var_calib_cam);
434 problem.AddResidualBlock(factor_prior,
nullptr, factor_params);
439 for (
auto const &feat : buffer_feats.at(n)) {
440 size_t featid = feat.first;
441 Eigen::Vector2d uv_raw;
442 uv_raw << feat.second(0), feat.second(1);
447 if (map_features.find(featid) == map_features.end()) {
449 Eigen::Vector3d p_FinG = sim.
get_map().at(featid);
450 auto *var_feat =
new double[3];
451 for (
int i = 0; i < 3; i++) {
452 std::normal_distribution<double> w(0, 1);
453 var_feat[i] = p_FinG(i) + feat_noise * w(gen_state_perturb);
455 map_features.insert({featid, (int)ceres_vars_feat.size()});
456 map_features_delayed.insert({featid, factpair()});
457 ceres_vars_feat.push_back(var_feat);
461 std::vector<double *> factor_params;
462 factor_params.push_back(ceres_vars_ori.at(map_states.at(timestamp_k1)));
463 factor_params.push_back(ceres_vars_pos.at(map_states.at(timestamp_k1)));
464 factor_params.push_back(ceres_vars_feat.at(map_features.at(featid)));
465 factor_params.push_back(ceres_vars_calib_cam2imu_ori.at(map_calib_cam2imu.at(cam_id)));
466 factor_params.push_back(ceres_vars_calib_cam2imu_pos.at(map_calib_cam2imu.at(cam_id)));
467 factor_params.push_back(ceres_vars_calib_cam_intrinsics.at(map_calib_cam.at(cam_id)));
469 if (map_features_delayed.find(featid) != map_features_delayed.end()) {
470 map_features_delayed.at(featid).push_back({factor_pinhole, factor_params});
472 ceres::LossFunction *loss_function =
nullptr;
474 problem.AddResidualBlock(factor_pinhole, loss_function, factor_params);
479 buffer_timecam = time_cam;
480 buffer_camids = camids;
481 buffer_feats = feats;
486 size_t min_num_meas_to_optimize = 10;
487 auto it0 = map_features_delayed.begin();
488 while (it0 != map_features_delayed.end()) {
489 size_t featid = (*it0).first;
490 auto factors = (*it0).second;
491 if (factors.size() >= min_num_meas_to_optimize) {
492 problem.AddParameterBlock(ceres_vars_feat.at(map_features.at(featid)), 3);
493 for (
auto const &factorpair : factors) {
494 auto factor_pinhole = factorpair.first;
495 auto factor_params = factorpair.second;
496 ceres::LossFunction *loss_function =
nullptr;
498 problem.AddResidualBlock(factor_pinhole, loss_function, factor_params);
500 it0 = map_features_delayed.erase(it0);
512 if (map_states.size() % 10 == 0 && map_states.size() > min_num_meas_to_optimize) {
515 double error_before = 0.0;
516 if (!map_features.empty()) {
517 for (
auto &feat : map_features) {
518 Eigen::Vector3d pos1, pos2;
519 pos1 << ceres_vars_feat.at(feat.second)[0], ceres_vars_feat.at(feat.second)[1], ceres_vars_feat.at(feat.second)[2];
520 pos2 = sim.
get_map().at(feat.first);
521 error_before += (pos2 - pos1).norm();
523 error_before /= (double)map_features.size();
527 ceres::Solver::Summary summary;
528 ceres::Solve(options, &problem, &summary);
529 PRINT_INFO(
"[CERES]: %s\n", summary.message.c_str());
530 PRINT_INFO(
"[CERES]: %d iterations | %zu states, %zu features | %d parameters and %d residuals | cost %.4e => %.4e\n",
531 (
int)summary.iterations.size(), map_states.size(), map_features.size(), summary.num_parameters, summary.num_residuals,
532 summary.initial_cost, summary.final_cost);
535 double error_after = 0.0;
536 if (!map_features.empty()) {
537 for (
auto &feat : map_features) {
538 Eigen::Vector3d pos1, pos2;
539 pos1 << ceres_vars_feat.at(feat.second)[0], ceres_vars_feat.at(feat.second)[1], ceres_vars_feat.at(feat.second)[2];
540 pos2 = sim.
get_map().at(feat.first);
541 error_after += (pos2 - pos1).norm();
543 error_after /= (double)map_features.size();
545 PRINT_INFO(
"[CERES]: map error %.4f => %.4f (meters) for %zu features\n", error_before, error_after, map_features.size());
559 #if ROS_AVAILABLE == 1
561 if (map_states.size() % 1 == 0) {
564 nav_msgs::Path arrEST, arrGT;
566 arrEST.header.frame_id =
"global";
568 arrGT.header.frame_id =
"global";
569 for (
auto &statepair : map_states) {
570 geometry_msgs::PoseStamped poseEST, poseGT;
571 poseEST.header.stamp =
ros::Time(statepair.first);
572 poseEST.header.frame_id =
"global";
573 poseEST.pose.orientation.x = ceres_vars_ori[statepair.second][0];
574 poseEST.pose.orientation.y = ceres_vars_ori[statepair.second][1];
575 poseEST.pose.orientation.z = ceres_vars_ori[statepair.second][2];
576 poseEST.pose.orientation.w = ceres_vars_ori[statepair.second][3];
577 poseEST.pose.position.x = ceres_vars_pos[statepair.second][0];
578 poseEST.pose.position.y = ceres_vars_pos[statepair.second][1];
579 poseEST.pose.position.z = ceres_vars_pos[statepair.second][2];
580 Eigen::Matrix<double, 17, 1> gt_imustate;
583 poseGT.header.stamp =
ros::Time(statepair.first);
584 poseGT.header.frame_id =
"global";
585 poseGT.pose.orientation.x = gt_imustate(1);
586 poseGT.pose.orientation.y = gt_imustate(2);
587 poseGT.pose.orientation.z = gt_imustate(3);
588 poseGT.pose.orientation.w = gt_imustate(4);
589 poseGT.pose.position.x = gt_imustate(5);
590 poseGT.pose.position.y = gt_imustate(6);
591 poseGT.pose.position.z = gt_imustate(7);
592 arrEST.poses.push_back(poseEST);
593 arrGT.poses.push_back(poseGT);
595 pub_pathimu.publish(arrEST);
596 pub_pathgt.publish(arrGT);
599 sensor_msgs::PointCloud point_cloud;
600 point_cloud.header.frame_id =
"global";
602 for (
auto &featpair : map_features) {
603 if (map_features_delayed.find(featpair.first) != map_features_delayed.end())
605 geometry_msgs::Point32 p;
606 p.x = (float)ceres_vars_feat[map_features[featpair.first]][0];
607 p.y = (
float)ceres_vars_feat[map_features[featpair.first]][1];
608 p.z = (float)ceres_vars_feat[map_features[featpair.first]][2];
609 point_cloud.points.push_back(p);
611 pub_loop_point.publish(point_cloud);
614 sensor_msgs::PointCloud2 cloud;
615 cloud.header.frame_id =
"global";
617 cloud.width = map_features.size();
619 cloud.is_bigendian =
false;
620 cloud.is_dense =
false;
623 modifier.
resize(map_features.size());
627 for (
auto &featpair : map_features) {
628 if (map_features_delayed.find(featpair.first) != map_features_delayed.end())
630 *out_x = (float)sim.
get_map().at(featpair.first)(0);
632 *out_y = (float)sim.
get_map().at(featpair.first)(1);
634 *out_z = (float)sim.
get_map().at(featpair.first)(2);
637 pub_points_sim.publish(cloud);