50 VioManager::VioManager(
VioManagerOptions ¶ms_) : thread_init_running(false), thread_init_success(false) {
53 PRINT_DEBUG(
"=======================================\n");
54 PRINT_DEBUG(
"OPENVINS ON-MANIFOLD EKF IS STARTING\n");
55 PRINT_DEBUG(
"=======================================\n");
85 Eigen::VectorXd temp_camimu_dt;
86 temp_camimu_dt.resize(1);
88 state->_calib_dt_CAMtoIMU->set_value(temp_camimu_dt);
89 state->_calib_dt_CAMtoIMU->set_fej(temp_camimu_dt);
93 for (
int i = 0; i <
state->_options.num_cameras; i++) {
113 boost::filesystem::create_directories(p.parent_path());
117 of_statistics <<
"# timestamp (sec),tracking,propagation,msckf update,";
118 if (
state->_options.max_slam_features > 0) {
170 double oldest_time =
state->margtimestep();
171 if (oldest_time >
state->_timestamp) {
192 const std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>> &feats) {
195 rT1 = boost::posix_time::microsec_clock::local_time();
199 std::shared_ptr<TrackSIM> trackSIM = std::dynamic_pointer_cast<TrackSIM>(
trackFEATS);
200 if (trackSIM ==
nullptr) {
202 trackSIM = std::make_shared<TrackSIM>(
state->_cam_intrinsics_cameras,
state->_options.max_aruco_features);
215 trackSIM->feed_measurement_simulation(timestamp, camids, feats);
216 rT2 = boost::posix_time::microsec_clock::local_time();
223 if (
state->_timestamp != timestamp) {
227 assert(
state->_timestamp == timestamp);
228 propagator->clean_old_imu_measurements(timestamp +
state->_calib_dt_CAMtoIMU->value()(0) - 0.10);
229 updaterZUPT->clean_old_imu_measurements(timestamp +
state->_calib_dt_CAMtoIMU->value()(0) - 0.10);
237 PRINT_ERROR(
RED "[SIM]: your vio system should already be initialized before simulating features!!!\n" RESET);
238 PRINT_ERROR(
RED "[SIM]: initialize your system first before calling feed_measurement_simulation()!!!!\n" RESET);
239 std::exit(EXIT_FAILURE);
246 for (
auto const &camid : camids) {
247 int width =
state->_cam_intrinsics_cameras.at(camid)->w();
248 int height =
state->_cam_intrinsics_cameras.at(camid)->h();
250 message.
images.push_back(cv::Mat::zeros(cv::Size(width, height), CV_8UC1));
251 message.
masks.push_back(cv::Mat::zeros(cv::Size(width, height), CV_8UC1));
259 rT1 = boost::posix_time::microsec_clock::local_time();
264 for (
size_t i = 0; i < message_const.
sensor_ids.size() - 1; i++) {
271 cv::Mat img = message.
images.at(i);
272 cv::Mat mask = message.
masks.at(i);
273 cv::Mat img_temp, mask_temp;
274 cv::pyrDown(img, img_temp, cv::Size(img.cols / 2.0, img.rows / 2.0));
275 message.
images.at(i) = img_temp;
276 cv::pyrDown(mask, mask_temp, cv::Size(mask.cols / 2.0, mask.rows / 2.0));
277 message.
masks.at(i) = mask_temp;
289 rT2 = boost::posix_time::microsec_clock::local_time();
313 double time_track = (
rT2 -
rT1).total_microseconds() * 1e-6;
343 rT3 = boost::posix_time::microsec_clock::local_time();
348 if ((
int)
state->_clones_IMU.size() < std::min(
state->_options.max_clone_size, 5)) {
349 PRINT_DEBUG(
"waiting for enough clone states (%d of %d)....\n", (
int)
state->_clones_IMU.size(),
350 std::min(
state->_options.max_clone_size, 5));
368 std::vector<std::shared_ptr<Feature>> feats_lost, feats_marg, feats_slam;
369 feats_lost =
trackFEATS->get_feature_database()->features_not_containing_newer(
state->_timestamp,
false,
true);
372 if ((
int)
state->_clones_IMU.size() >
state->_options.max_clone_size || (
int)
state->_clones_IMU.size() > 5) {
373 feats_marg =
trackFEATS->get_feature_database()->features_containing(
state->margtimestep(),
false,
true);
375 feats_slam =
trackARUCO->get_feature_database()->features_containing(
state->margtimestep(),
false,
true);
382 auto it1 = feats_lost.begin();
383 while (it1 != feats_lost.end()) {
384 bool found_current_message_camid =
false;
385 for (
const auto &camuvpair : (*it1)->uvs) {
387 found_current_message_camid =
true;
391 if (found_current_message_camid) {
394 it1 = feats_lost.erase(it1);
400 it1 = feats_lost.begin();
401 while (it1 != feats_lost.end()) {
402 if (std::find(feats_marg.begin(), feats_marg.end(), (*it1)) != feats_marg.end()) {
404 it1 = feats_lost.erase(it1);
411 std::vector<std::shared_ptr<Feature>> feats_maxtracks;
412 auto it2 = feats_marg.begin();
413 while (it2 != feats_marg.end()) {
415 bool reached_max =
false;
416 for (
const auto &cams : (*it2)->timestamps) {
417 if ((
int)cams.second.size() >
state->_options.max_clone_size) {
424 feats_maxtracks.push_back(*it2);
425 it2 = feats_marg.erase(it2);
432 int curr_aruco_tags = 0;
433 auto it0 =
state->_features_SLAM.begin();
434 while (it0 !=
state->_features_SLAM.end()) {
435 if ((
int)(*it0).second->_featid <= 4 *
state->_options.max_aruco_features)
443 (
int)
state->_features_SLAM.size() <
state->_options.max_slam_features + curr_aruco_tags) {
445 int amount_to_add = (
state->_options.max_slam_features + curr_aruco_tags) - (
int)
state->_features_SLAM.size();
446 int valid_amount = (amount_to_add > (int)feats_maxtracks.size()) ? (
int)feats_maxtracks.size() : amount_to_add;
449 if (valid_amount > 0) {
450 feats_slam.insert(feats_slam.end(), feats_maxtracks.end() - valid_amount, feats_maxtracks.end());
451 feats_maxtracks.erase(feats_maxtracks.end() - valid_amount, feats_maxtracks.end());
460 for (std::pair<
const size_t, std::shared_ptr<Landmark>> &landmark :
state->_features_SLAM) {
462 std::shared_ptr<Feature> feat1 =
trackARUCO->get_feature_database()->get_feature(landmark.second->_featid);
463 if (feat1 !=
nullptr)
464 feats_slam.push_back(feat1);
466 std::shared_ptr<Feature> feat2 =
trackFEATS->get_feature_database()->get_feature(landmark.second->_featid);
467 if (feat2 !=
nullptr)
468 feats_slam.push_back(feat2);
469 assert(landmark.second->_unique_camera_id != -1);
470 bool current_unique_cam =
472 if (feat2 ==
nullptr && current_unique_cam)
473 landmark.second->should_marg =
true;
474 if (landmark.second->update_fail_count > 1)
475 landmark.second->should_marg =
true;
484 std::vector<std::shared_ptr<Feature>> feats_slam_DELAYED, feats_slam_UPDATE;
485 for (
size_t i = 0; i < feats_slam.size(); i++) {
486 if (
state->_features_SLAM.find(feats_slam.at(i)->featid) !=
state->_features_SLAM.end()) {
487 feats_slam_UPDATE.push_back(feats_slam.at(i));
491 feats_slam_DELAYED.push_back(feats_slam.at(i));
498 std::vector<std::shared_ptr<Feature>> featsup_MSCKF = feats_lost;
499 featsup_MSCKF.insert(featsup_MSCKF.end(), feats_marg.begin(), feats_marg.end());
500 featsup_MSCKF.insert(featsup_MSCKF.end(), feats_maxtracks.begin(), feats_maxtracks.end());
509 auto compare_feat = [](
const std::shared_ptr<Feature> &a,
const std::shared_ptr<Feature> &b) ->
bool {
512 for (
const auto &pair : a->timestamps)
513 asize += pair.second.size();
514 for (
const auto &pair : b->timestamps)
515 bsize += pair.second.size();
516 return asize < bsize;
518 std::sort(featsup_MSCKF.begin(), featsup_MSCKF.end(), compare_feat);
523 if ((
int)featsup_MSCKF.size() >
state->_options.max_msckf_in_update)
524 featsup_MSCKF.erase(featsup_MSCKF.begin(), featsup_MSCKF.end() -
state->_options.max_msckf_in_update);
527 rT4 = boost::posix_time::microsec_clock::local_time();
532 std::vector<std::shared_ptr<Feature>> feats_slam_UPDATE_TEMP;
533 while (!feats_slam_UPDATE.empty()) {
535 std::vector<std::shared_ptr<Feature>> featsup_TEMP;
536 featsup_TEMP.insert(featsup_TEMP.begin(), feats_slam_UPDATE.begin(),
537 feats_slam_UPDATE.begin() + std::min(
state->_options.max_slam_in_update, (
int)feats_slam_UPDATE.size()));
538 feats_slam_UPDATE.erase(feats_slam_UPDATE.begin(),
539 feats_slam_UPDATE.begin() + std::min(
state->_options.max_slam_in_update, (
int)feats_slam_UPDATE.size()));
542 feats_slam_UPDATE_TEMP.insert(feats_slam_UPDATE_TEMP.end(), featsup_TEMP.begin(), featsup_TEMP.end());
545 feats_slam_UPDATE = feats_slam_UPDATE_TEMP;
546 rT5 = boost::posix_time::microsec_clock::local_time();
548 rT6 = boost::posix_time::microsec_clock::local_time();
567 for (
auto const &feat : featsup_MSCKF) {
569 feat->to_delete =
true;
579 trackFEATS->get_feature_database()->cleanup();
581 trackARUCO->get_feature_database()->cleanup();
588 if ((
int)
state->_clones_IMU.size() >
state->_options.max_clone_size) {
589 trackFEATS->get_feature_database()->cleanup_measurements(
state->margtimestep());
591 trackARUCO->get_feature_database()->cleanup_measurements(
state->margtimestep());
597 rT7 = boost::posix_time::microsec_clock::local_time();
604 double time_track = (
rT2 -
rT1).total_microseconds() * 1e-6;
605 double time_prop = (
rT3 -
rT2).total_microseconds() * 1e-6;
606 double time_msckf = (
rT4 -
rT3).total_microseconds() * 1e-6;
607 double time_slam_update = (
rT5 -
rT4).total_microseconds() * 1e-6;
608 double time_slam_delay = (
rT6 -
rT5).total_microseconds() * 1e-6;
609 double time_marg = (
rT7 -
rT6).total_microseconds() * 1e-6;
610 double time_total = (
rT7 -
rT1).total_microseconds() * 1e-6;
615 PRINT_DEBUG(
BLUE "[TIME]: %.4f seconds for MSCKF update (%d feats)\n" RESET, time_msckf, (
int)featsup_MSCKF.size());
616 if (
state->_options.max_slam_features > 0) {
617 PRINT_DEBUG(
BLUE "[TIME]: %.4f seconds for SLAM update (%d feats)\n" RESET, time_slam_update, (
int)
state->_features_SLAM.size());
618 PRINT_DEBUG(
BLUE "[TIME]: %.4f seconds for SLAM delayed init (%d feats)\n" RESET, time_slam_delay, (
int)feats_slam_DELAYED.size());
620 PRINT_DEBUG(
BLUE "[TIME]: %.4f seconds for re-tri & marg (%d clones in state)\n" RESET, time_marg, (
int)
state->_clones_IMU.size());
622 std::stringstream ss;
623 ss <<
"[TIME]: " << std::setprecision(4) << time_total <<
" seconds for total (camera";
627 ss <<
")" << std::endl;
634 double t_ItoC =
state->_calib_dt_CAMtoIMU->value()(0);
635 double timestamp_inI =
state->_timestamp + t_ItoC;
637 of_statistics << std::fixed << std::setprecision(15) << timestamp_inI <<
"," << std::fixed << std::setprecision(5) << time_track <<
","
638 << time_prop <<
"," << time_msckf <<
",";
639 if (
state->_options.max_slam_features > 0) {
640 of_statistics << time_slam_update <<
"," << time_slam_delay <<
",";
642 of_statistics << time_marg <<
"," << time_total << std::endl;
654 PRINT_INFO(
"q_GtoI = %.3f,%.3f,%.3f,%.3f | p_IinG = %.3f,%.3f,%.3f | dist = %.2f (meters)\n",
state->_imu->quat()(0),
657 PRINT_INFO(
"bg = %.4f,%.4f,%.4f | ba = %.4f,%.4f,%.4f\n",
state->_imu->bias_g()(0),
state->_imu->bias_g()(1),
state->_imu->bias_g()(2),
658 state->_imu->bias_a()(0),
state->_imu->bias_a()(1),
state->_imu->bias_a()(2));
661 if (
state->_options.do_calib_camera_timeoffset) {
662 PRINT_INFO(
"camera-imu timeoffset = %.5f\n",
state->_calib_dt_CAMtoIMU->value()(0));
666 if (
state->_options.do_calib_camera_intrinsics) {
667 for (
int i = 0; i <
state->_options.num_cameras; i++) {
668 std::shared_ptr<Vec> calib =
state->_cam_intrinsics.at(i);
669 PRINT_INFO(
"cam%d intrinsics = %.3f,%.3f,%.3f,%.3f | %.3f,%.3f,%.3f,%.3f\n", (
int)i, calib->value()(0), calib->value()(1),
670 calib->value()(2), calib->value()(3), calib->value()(4), calib->value()(5), calib->value()(6), calib->value()(7));
675 if (
state->_options.do_calib_camera_pose) {
676 for (
int i = 0; i <
state->_options.num_cameras; i++) {
677 std::shared_ptr<PoseJPL> calib =
state->_calib_IMUtoCAM.at(i);
678 PRINT_INFO(
"cam%d extrinsics = %.3f,%.3f,%.3f,%.3f | %.3f,%.3f,%.3f\n", (
int)i, calib->quat()(0), calib->quat()(1), calib->quat()(2),
679 calib->quat()(3), calib->pos()(0), calib->pos()(1), calib->pos()(2));
684 if (
state->_options.do_calib_imu_intrinsics &&
state->_options.imu_model == StateOptions::ImuModel::KALIBR) {
685 PRINT_INFO(
"q_GYROtoI = %.3f,%.3f,%.3f,%.3f\n",
state->_calib_imu_GYROtoIMU->value()(0),
state->_calib_imu_GYROtoIMU->value()(1),
686 state->_calib_imu_GYROtoIMU->value()(2),
state->_calib_imu_GYROtoIMU->value()(3));
688 if (
state->_options.do_calib_imu_intrinsics &&
state->_options.imu_model == StateOptions::ImuModel::RPNG) {
689 PRINT_INFO(
"q_ACCtoI = %.3f,%.3f,%.3f,%.3f\n",
state->_calib_imu_ACCtoIMU->value()(0),
state->_calib_imu_ACCtoIMU->value()(1),
690 state->_calib_imu_ACCtoIMU->value()(2),
state->_calib_imu_ACCtoIMU->value()(3));
692 if (
state->_options.do_calib_imu_intrinsics &&
state->_options.imu_model == StateOptions::ImuModel::KALIBR) {
693 PRINT_INFO(
"Dw = | %.4f,%.4f,%.4f | %.4f,%.4f | %.4f |\n",
state->_calib_imu_dw->value()(0),
state->_calib_imu_dw->value()(1),
694 state->_calib_imu_dw->value()(2),
state->_calib_imu_dw->value()(3),
state->_calib_imu_dw->value()(4),
695 state->_calib_imu_dw->value()(5));
696 PRINT_INFO(
"Da = | %.4f,%.4f,%.4f | %.4f,%.4f | %.4f |\n",
state->_calib_imu_da->value()(0),
state->_calib_imu_da->value()(1),
697 state->_calib_imu_da->value()(2),
state->_calib_imu_da->value()(3),
state->_calib_imu_da->value()(4),
698 state->_calib_imu_da->value()(5));
700 if (
state->_options.do_calib_imu_intrinsics &&
state->_options.imu_model == StateOptions::ImuModel::RPNG) {
701 PRINT_INFO(
"Dw = | %.4f | %.4f,%.4f | %.4f,%.4f,%.4f |\n",
state->_calib_imu_dw->value()(0),
state->_calib_imu_dw->value()(1),
702 state->_calib_imu_dw->value()(2),
state->_calib_imu_dw->value()(3),
state->_calib_imu_dw->value()(4),
703 state->_calib_imu_dw->value()(5));
704 PRINT_INFO(
"Da = | %.4f | %.4f,%.4f | %.4f,%.4f,%.4f |\n",
state->_calib_imu_da->value()(0),
state->_calib_imu_da->value()(1),
705 state->_calib_imu_da->value()(2),
state->_calib_imu_da->value()(3),
state->_calib_imu_da->value()(4),
706 state->_calib_imu_da->value()(5));
708 if (
state->_options.do_calib_imu_intrinsics &&
state->_options.do_calib_imu_g_sensitivity) {
709 PRINT_INFO(
"Tg = | %.4f,%.4f,%.4f | %.4f,%.4f,%.4f | %.4f,%.4f,%.4f |\n",
state->_calib_imu_tg->value()(0),
710 state->_calib_imu_tg->value()(1),
state->_calib_imu_tg->value()(2),
state->_calib_imu_tg->value()(3),
711 state->_calib_imu_tg->value()(4),
state->_calib_imu_tg->value()(5),
state->_calib_imu_tg->value()(6),
712 state->_calib_imu_tg->value()(7),
state->_calib_imu_tg->value()(8));