36 #include <boost/date_time/posix_time/posix_time.hpp>
37 #include <boost/math/distributions/chi_squared.hpp>
44 : _options_slam(options_slam), _options_aruco(options_aruco) {
55 for (
int i = 1; i < 500; i++) {
56 boost::math::chi_squared chi_squared_dist(i);
64 if (feature_vec.empty())
68 boost::posix_time::ptime rT0, rT1, rT2, rT3;
69 rT0 = boost::posix_time::microsec_clock::local_time();
73 for (
const auto &clone_imu : state->_clones_IMU) {
78 auto it0 = feature_vec.begin();
79 while (it0 != feature_vec.end()) {
86 for (
const auto &pair : (*it0)->timestamps) {
87 ct_meas += (*it0)->timestamps[pair.first].size();
92 (*it0)->to_delete =
true;
93 it0 = feature_vec.erase(it0);
98 rT1 = boost::posix_time::microsec_clock::local_time();
101 std::unordered_map<size_t, std::unordered_map<double, FeatureInitializer::ClonePose>> clones_cam;
102 for (
const auto &clone_calib : state->_calib_IMUtoCAM) {
105 std::unordered_map<double, FeatureInitializer::ClonePose> clones_cami;
106 for (
const auto &clone_imu : state->_clones_IMU) {
109 Eigen::Matrix<double, 3, 3> R_GtoCi = clone_calib.second->Rot() * clone_imu.second->Rot();
110 Eigen::Matrix<double, 3, 1> p_CioinG = clone_imu.second->pos() - R_GtoCi.transpose() * clone_calib.second->pos();
113 clones_cami.insert({clone_imu.first, FeatureInitializer::ClonePose(R_GtoCi, p_CioinG)});
117 clones_cam.insert({clone_calib.first, clones_cami});
121 auto it1 = feature_vec.begin();
122 while (it1 != feature_vec.end()) {
125 bool success_tri =
true;
133 bool success_refine =
true;
139 if (!success_tri || !success_refine) {
140 (*it1)->to_delete =
true;
141 it1 = feature_vec.erase(it1);
146 rT2 = boost::posix_time::microsec_clock::local_time();
149 auto it2 = feature_vec.begin();
150 while (it2 != feature_vec.end()) {
154 feat.
featid = (*it2)->featid;
155 feat.
uvs = (*it2)->uvs;
161 ((int)feat.
featid < state->_options.max_aruco_features) ? state->_options.feat_rep_aruco : state->_options.feat_rep_slam;
163 if (feat_rep == LandmarkRepresentation::Representation::ANCHORED_INVERSE_DEPTH_SINGLE) {
164 feat.
feat_representation = LandmarkRepresentation::Representation::ANCHORED_MSCKF_INVERSE_DEPTH;
171 feat.
p_FinA = (*it2)->p_FinA;
174 feat.
p_FinG = (*it2)->p_FinG;
182 std::vector<std::shared_ptr<Type>> Hx_order;
190 if (feat_rep == LandmarkRepresentation::Representation::ANCHORED_INVERSE_DEPTH_SINGLE) {
193 Eigen::MatrixXd H_xf = H_x;
194 H_xf.conservativeResize(H_x.rows(), H_x.cols() + 1);
195 H_xf.block(0, H_x.cols(), H_x.rows(), 1) = H_f.block(0, H_f.cols() - 1, H_f.rows(), 1);
196 H_f.conservativeResize(H_f.rows(), H_f.cols() - 1);
204 H_x = H_xf.block(0, 0, H_xf.rows(), H_xf.cols() - 1);
205 H_f = H_xf.block(0, H_xf.cols() - 1, H_xf.rows(), 1);
210 int landmark_size = (feat_rep == LandmarkRepresentation::Representation::ANCHORED_INVERSE_DEPTH_SINGLE) ? 1 : 3;
211 auto landmark = std::make_shared<Landmark>(landmark_size);
212 landmark->_featid = feat.
featid;
213 landmark->_feat_representation = feat_rep;
214 landmark->_unique_camera_id = (*it2)->anchor_cam_id;
218 landmark->set_from_xyz(feat.
p_FinA,
false);
219 landmark->set_from_xyz(feat.
p_FinA_fej,
true);
221 landmark->set_from_xyz(feat.
p_FinG,
false);
222 landmark->set_from_xyz(feat.
p_FinG_fej,
true);
226 double sigma_pix_sq =
228 Eigen::MatrixXd R = sigma_pix_sq * Eigen::MatrixXd::Identity(res.rows(), res.rows());
231 double chi2_multipler =
234 state->_features_SLAM.insert({(*it2)->featid, landmark});
235 (*it2)->to_delete =
true;
238 (*it2)->to_delete =
true;
239 it2 = feature_vec.erase(it2);
242 rT3 = boost::posix_time::microsec_clock::local_time();
245 if (!feature_vec.empty()) {
246 PRINT_ALL(
"[SLAM-DELAY]: %.4f seconds to clean\n", (rT1 - rT0).total_microseconds() * 1e-6);
247 PRINT_ALL(
"[SLAM-DELAY]: %.4f seconds to triangulate\n", (rT2 - rT1).total_microseconds() * 1e-6);
248 PRINT_ALL(
"[SLAM-DELAY]: %.4f seconds initialize (%d features)\n", (rT3 - rT2).total_microseconds() * 1e-6, (
int)feature_vec.size());
249 PRINT_ALL(
"[SLAM-DELAY]: %.4f seconds total\n", (rT3 - rT1).total_microseconds() * 1e-6);
253 void UpdaterSLAM::update(std::shared_ptr<State> state, std::vector<std::shared_ptr<Feature>> &feature_vec) {
256 if (feature_vec.empty())
260 boost::posix_time::ptime rT0, rT1, rT2, rT3;
261 rT0 = boost::posix_time::microsec_clock::local_time();
265 for (
const auto &clone_imu : state->_clones_IMU) {
270 auto it0 = feature_vec.begin();
271 while (it0 != feature_vec.end()) {
278 for (
const auto &pair : (*it0)->timestamps) {
279 ct_meas += (*it0)->timestamps[pair.first].size();
285 std::shared_ptr<Landmark> landmark = state->_features_SLAM.at((*it0)->featid);
286 int required_meas = (landmark->_feat_representation == LandmarkRepresentation::Representation::ANCHORED_INVERSE_DEPTH_SINGLE) ? 2 : 1;
290 (*it0)->to_delete =
true;
291 it0 = feature_vec.erase(it0);
292 }
else if (ct_meas < required_meas) {
293 it0 = feature_vec.erase(it0);
298 rT1 = boost::posix_time::microsec_clock::local_time();
301 size_t max_meas_size = 0;
302 for (
size_t i = 0; i < feature_vec.size(); i++) {
303 for (
const auto &pair : feature_vec.at(i)->timestamps) {
304 max_meas_size += 2 * feature_vec.at(i)->timestamps[pair.first].size();
309 size_t max_hx_size = state->max_covariance_size();
312 Eigen::VectorXd res_big = Eigen::VectorXd::Zero(max_meas_size);
313 Eigen::MatrixXd Hx_big = Eigen::MatrixXd::Zero(max_meas_size, max_hx_size);
314 Eigen::MatrixXd R_big = Eigen::MatrixXd::Identity(max_meas_size, max_meas_size);
315 std::unordered_map<std::shared_ptr<Type>,
size_t> Hx_mapping;
316 std::vector<std::shared_ptr<Type>> Hx_order_big;
321 auto it2 = feature_vec.begin();
322 while (it2 != feature_vec.end()) {
325 assert(state->_features_SLAM.find((*it2)->featid) != state->_features_SLAM.end());
326 assert(state->_features_SLAM.at((*it2)->featid)->_featid == (*it2)->featid);
329 std::shared_ptr<Landmark> landmark = state->_features_SLAM.at((*it2)->featid);
333 feat.
featid = (*it2)->featid;
334 feat.
uvs = (*it2)->uvs;
340 if (landmark->_feat_representation == LandmarkRepresentation::Representation::ANCHORED_INVERSE_DEPTH_SINGLE) {
341 feat.
feat_representation = LandmarkRepresentation::Representation::ANCHORED_MSCKF_INVERSE_DEPTH;
348 feat.
p_FinA = landmark->get_xyz(
false);
351 feat.
p_FinG = landmark->get_xyz(
false);
359 std::vector<std::shared_ptr<Type>> Hx_order;
365 Eigen::MatrixXd H_xf = H_x;
366 if (landmark->_feat_representation == LandmarkRepresentation::Representation::ANCHORED_INVERSE_DEPTH_SINGLE) {
369 H_xf.conservativeResize(H_x.rows(), H_x.cols() + 1);
370 H_xf.block(0, H_x.cols(), H_x.rows(), 1) = H_f.block(0, H_f.cols() - 1, H_f.rows(), 1);
371 H_f.conservativeResize(H_f.rows(), H_f.cols() - 1);
381 H_xf.conservativeResize(H_x.rows(), H_x.cols() + H_f.cols());
382 H_xf.block(0, H_x.cols(), H_x.rows(), H_f.cols()) = H_f;
386 std::vector<std::shared_ptr<Type>> Hxf_order = Hx_order;
387 Hxf_order.push_back(landmark);
391 Eigen::MatrixXd S = H_xf * P_marg * H_xf.transpose();
392 double sigma_pix_sq =
394 S.diagonal() += sigma_pix_sq * Eigen::VectorXd::Ones(S.rows());
395 double chi2 = res.dot(S.llt().solve(res));
399 if (res.rows() < 500) {
402 boost::math::chi_squared chi_squared_dist(res.rows());
403 chi2_check = boost::math::quantile(chi_squared_dist, 0.95);
408 double chi2_multipler =
410 if (chi2 > chi2_multipler * chi2_check) {
411 if ((
int)feat.
featid < state->_options.max_aruco_features) {
413 chi2_multipler * chi2_check);
415 landmark->update_fail_count++;
417 (*it2)->to_delete =
true;
418 it2 = feature_vec.erase(it2);
423 if ((
int)feat.
featid < state->_options.max_aruco_features) {
424 PRINT_DEBUG(
"[SLAM-UP]: accepted aruco tag %d for chi2 thresh (%.3f < %.3f)\n", (
int)feat.
featid, chi2, chi2_multipler * chi2_check);
429 for (
const auto &var : Hxf_order) {
432 if (Hx_mapping.find(var) == Hx_mapping.end()) {
433 Hx_mapping.insert({var, ct_jacob});
434 Hx_order_big.push_back(var);
435 ct_jacob += var->size();
439 Hx_big.block(ct_meas, Hx_mapping[var], H_xf.rows(), var->size()) = H_xf.block(0, ct_hx, H_xf.rows(), var->size());
440 ct_hx += var->size();
444 R_big.block(ct_meas, ct_meas, res.rows(), res.rows()) *= sigma_pix_sq;
447 res_big.block(ct_meas, 0, res.rows(), 1) = res;
448 ct_meas += res.rows();
451 rT2 = boost::posix_time::microsec_clock::local_time();
455 for (
size_t f = 0;
f < feature_vec.size();
f++) {
456 feature_vec[
f]->to_delete =
true;
463 assert(ct_meas <= max_meas_size);
464 assert(ct_jacob <= max_hx_size);
465 res_big.conservativeResize(ct_meas, 1);
466 Hx_big.conservativeResize(ct_meas, ct_jacob);
467 R_big.conservativeResize(ct_meas, ct_meas);
471 rT3 = boost::posix_time::microsec_clock::local_time();
474 PRINT_ALL(
"[SLAM-UP]: %.4f seconds to clean\n", (rT1 - rT0).total_microseconds() * 1e-6);
475 PRINT_ALL(
"[SLAM-UP]: %.4f seconds creating linear system\n", (rT2 - rT1).total_microseconds() * 1e-6);
476 PRINT_ALL(
"[SLAM-UP]: %.4f seconds to update (%d feats of %d size)\n", (rT3 - rT2).total_microseconds() * 1e-6, (
int)feature_vec.size(),
478 PRINT_ALL(
"[SLAM-UP]: %.4f seconds total\n", (rT3 - rT1).total_microseconds() * 1e-6);
484 if ((
int)state->_clones_IMU.size() <= state->_options.max_clone_size) {
491 double marg_timestep = state->margtimestep();
492 for (
auto &
f : state->_features_SLAM) {
494 if (
f.second->_feat_representation == LandmarkRepresentation::Representation::GLOBAL_3D ||
495 f.second->_feat_representation == LandmarkRepresentation::Representation::GLOBAL_FULL_INVERSE_DEPTH)
498 assert(marg_timestep <= f.second->_anchor_clone_timestamp);
499 if (
f.second->_anchor_clone_timestamp == marg_timestep) {
509 assert(LandmarkRepresentation::is_relative_representation(landmark->_feat_representation));
510 assert(landmark->_anchor_cam_id != -1);
514 old_feat.
featid = landmark->_featid;
518 old_feat.
p_FinA = landmark->get_xyz(
false);
519 old_feat.
p_FinA_fej = landmark->get_xyz(
true);
522 Eigen::MatrixXd H_f_old;
523 std::vector<Eigen::MatrixXd> H_x_old;
524 std::vector<std::shared_ptr<Type>> x_order_old;
529 new_feat.
featid = landmark->_featid;
539 Eigen::Matrix<double, 3, 3> R_GtoOLD = state->_calib_IMUtoCAM.at(old_feat.
anchor_cam_id)->Rot() * R_GtoIOLD;
541 R_GtoOLD.transpose() * state->_calib_IMUtoCAM.at(old_feat.
anchor_cam_id)->pos();
545 Eigen::Matrix<double, 3, 3> R_GtoNEW = state->_calib_IMUtoCAM.at(new_feat.
anchor_cam_id)->Rot() * R_GtoINEW;
547 R_GtoNEW.transpose() * state->_calib_IMUtoCAM.at(new_feat.
anchor_cam_id)->pos();
550 Eigen::Matrix<double, 3, 3> R_OLDtoNEW = R_GtoNEW * R_GtoOLD.transpose();
551 Eigen::Matrix<double, 3, 1> p_OLDinNEW = R_GtoNEW * (p_OLDinG - p_NEWinG);
552 new_feat.
p_FinA = R_OLDtoNEW * landmark->get_xyz(
false) + p_OLDinNEW;
558 Eigen::Matrix<double, 3, 3> R_GtoIOLD_fej = state->_clones_IMU.at(old_feat.
anchor_clone_timestamp)->Rot_fej();
559 Eigen::Matrix<double, 3, 3> R_GtoOLD_fej = state->_calib_IMUtoCAM.at(old_feat.
anchor_cam_id)->Rot() * R_GtoIOLD_fej;
560 Eigen::Matrix<double, 3, 1> p_OLDinG_fej = state->_clones_IMU.at(old_feat.
anchor_clone_timestamp)->pos_fej() -
561 R_GtoOLD_fej.transpose() * state->_calib_IMUtoCAM.at(old_feat.
anchor_cam_id)->pos();
564 Eigen::Matrix<double, 3, 3> R_GtoINEW_fej = state->_clones_IMU.at(new_feat.
anchor_clone_timestamp)->Rot_fej();
565 Eigen::Matrix<double, 3, 3> R_GtoNEW_fej = state->_calib_IMUtoCAM.at(new_feat.
anchor_cam_id)->Rot() * R_GtoINEW_fej;
566 Eigen::Matrix<double, 3, 1> p_NEWinG_fej = state->_clones_IMU.at(new_feat.
anchor_clone_timestamp)->pos_fej() -
567 R_GtoNEW_fej.transpose() * state->_calib_IMUtoCAM.at(new_feat.
anchor_cam_id)->pos();
570 Eigen::Matrix<double, 3, 3> R_OLDtoNEW_fej = R_GtoNEW_fej * R_GtoOLD_fej.transpose();
571 Eigen::Matrix<double, 3, 1> p_OLDinNEW_fej = R_GtoNEW_fej * (p_OLDinG_fej - p_NEWinG_fej);
572 new_feat.
p_FinA_fej = R_OLDtoNEW_fej * landmark->get_xyz(
true) + p_OLDinNEW_fej;
575 Eigen::MatrixXd H_f_new;
576 std::vector<Eigen::MatrixXd> H_x_new;
577 std::vector<std::shared_ptr<Type>> x_order_new;
584 std::vector<std::shared_ptr<Type>> phi_order_NEW;
585 phi_order_NEW.push_back(landmark);
588 std::vector<std::shared_ptr<Type>> phi_order_OLD;
590 std::map<std::shared_ptr<Type>,
int> Phi_id_map;
591 for (
const auto &var : x_order_old) {
592 if (Phi_id_map.find(var) == Phi_id_map.end()) {
593 Phi_id_map.insert({var, current_it});
594 phi_order_OLD.push_back(var);
595 current_it += var->size();
598 for (
const auto &var : x_order_new) {
599 if (Phi_id_map.find(var) == Phi_id_map.end()) {
600 Phi_id_map.insert({var, current_it});
601 phi_order_OLD.push_back(var);
602 current_it += var->size();
605 Phi_id_map.insert({landmark, current_it});
606 phi_order_OLD.push_back(landmark);
607 current_it += landmark->size();
610 int phisize = (new_feat.
feat_representation != LandmarkRepresentation::Representation::ANCHORED_INVERSE_DEPTH_SINGLE) ? 3 : 1;
611 Eigen::MatrixXd Phi = Eigen::MatrixXd::Zero(phisize, current_it);
612 Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(phisize, phisize);
616 Eigen::MatrixXd H_f_new_inv;
618 H_f_new_inv = 1.0 / H_f_new.squaredNorm() * H_f_new.transpose();
620 H_f_new_inv = H_f_new.colPivHouseholderQr().solve(Eigen::Matrix<double, 3, 3>::Identity());
624 for (
size_t i = 0; i < H_x_old.size(); i++) {
625 Phi.block(0, Phi_id_map.at(x_order_old[i]), phisize, x_order_old[i]->size()).noalias() += H_f_new_inv * H_x_old[i];
629 Phi.block(0, Phi_id_map.at(landmark), phisize, phisize) = H_f_new_inv * H_f_old;
632 for (
size_t i = 0; i < H_x_new.size(); i++) {
633 Phi.block(0, Phi_id_map.at(x_order_new[i]), phisize, x_order_new[i]->size()).noalias() -= H_f_new_inv * H_x_new[i];
640 landmark->_featid = new_feat.
featid;
644 landmark->set_from_xyz(new_feat.
p_FinA,
false);
645 landmark->set_from_xyz(new_feat.
p_FinA_fej,
true);
646 landmark->has_had_anchor_change =
true;