35 #include <boost/date_time/posix_time/posix_time.hpp>
36 #include <boost/math/distributions/chi_squared.hpp>
43 std::shared_ptr<Propagator> prop,
double gravity_mag,
double zupt_max_velocity,
44 double zupt_noise_multiplier,
double zupt_max_disparity)
45 : _options(options), _noises(noises), _db(db), _prop(prop), _zupt_max_velocity(zupt_max_velocity),
46 _zupt_noise_multiplier(zupt_noise_multiplier), _zupt_max_disparity(zupt_max_disparity) {
59 for (
int i = 1; i < 1000; i++) {
60 boost::math::chi_squared chi_squared_dist(i);
74 if (state->_timestamp == timestamp) {
89 double t_off_new = state->_calib_dt_CAMtoIMU->value()(0);
94 double time1 = timestamp + t_off_new;
103 if (imu_recent.size() < 2) {
111 bool integrated_accel_constraint =
false;
112 bool model_time_varying_bias =
true;
113 bool override_with_disparity_check =
true;
114 bool explicitly_enforce_zero_motion =
false;
117 std::vector<std::shared_ptr<Type>> Hx_order;
118 Hx_order.push_back(state->_imu->q());
119 Hx_order.push_back(state->_imu->bg());
120 Hx_order.push_back(state->_imu->ba());
121 if (integrated_accel_constraint) {
122 Hx_order.push_back(state->_imu->v());
126 int h_size = (integrated_accel_constraint) ? 12 : 9;
127 int m_size = 6 * ((int)imu_recent.size() - 1);
128 Eigen::MatrixXd H = Eigen::MatrixXd::Zero(m_size, h_size);
129 Eigen::VectorXd res = Eigen::VectorXd::Zero(m_size);
132 Eigen::Matrix3d Dw =
State::Dm(state->_options.imu_model, state->_calib_imu_dw->value());
133 Eigen::Matrix3d Da =
State::Dm(state->_options.imu_model, state->_calib_imu_da->value());
134 Eigen::Matrix3d Tg =
State::Tg(state->_calib_imu_tg->value());
143 double dt_summed = 0;
144 for (
size_t i = 0; i < imu_recent.size() - 1; i++) {
147 double dt = imu_recent.at(i + 1).timestamp - imu_recent.at(i).timestamp;
148 Eigen::Vector3d a_hat = state->_calib_imu_ACCtoIMU->Rot() * Da * (imu_recent.at(i).am - state->_imu->bias_a());
149 Eigen::Vector3d w_hat = state->_calib_imu_GYROtoIMU->Rot() * Dw * (imu_recent.at(i).wm - state->_imu->bias_g() - Tg * a_hat);
161 res.block(6 * i + 0, 0, 3, 1) = -w_omega * w_hat;
162 if (!integrated_accel_constraint) {
163 res.block(6 * i + 3, 0, 3, 1) = -w_accel * (a_hat - state->_imu->Rot() *
_gravity);
165 res.block(6 * i + 3, 0, 3, 1) = -w_accel_v * (state->_imu->vel() -
_gravity * dt + state->_imu->Rot().transpose() * a_hat * dt);
169 Eigen::Matrix3d R_GtoI_jacob = (state->_options.do_fej) ? state->_imu->Rot_fej() : state->_imu->Rot();
170 H.block(6 * i + 0, 3, 3, 3) = -w_omega * Eigen::Matrix3d::Identity();
171 if (!integrated_accel_constraint) {
172 H.block(6 * i + 3, 0, 3, 3) = -w_accel *
skew_x(R_GtoI_jacob *
_gravity);
173 H.block(6 * i + 3, 6, 3, 3) = -w_accel * Eigen::Matrix3d::Identity();
175 H.block(6 * i + 3, 0, 3, 3) = -w_accel_v * R_GtoI_jacob.transpose() *
skew_x(a_hat) * dt;
176 H.block(6 * i + 3, 6, 3, 3) = -w_accel_v * R_GtoI_jacob.transpose() * dt;
177 H.block(6 * i + 3, 9, 3, 3) = w_accel_v * Eigen::Matrix3d::Identity();
194 Eigen::MatrixXd Q_bias = Eigen::MatrixXd::Identity(6, 6);
202 if (model_time_varying_bias) {
203 P_marg.block(3, 3, 6, 6) += Q_bias;
205 Eigen::MatrixXd S = H * P_marg * H.transpose() + R;
206 double chi2 = res.dot(S.llt().solve(res));
210 if (res.rows() < 1000) {
213 boost::math::chi_squared chi_squared_dist(res.rows());
214 chi2_check = boost::math::quantile(chi_squared_dist, 0.95);
219 bool disparity_passed =
false;
220 if (override_with_disparity_check) {
223 double time0_cam = state->_timestamp;
224 double time1_cam = timestamp;
225 int num_features = 0;
226 double disp_avg = 0.0;
227 double disp_var = 0.0;
228 FeatureHelper::compute_disparity(
_db, time0_cam, time1_cam, disp_avg, disp_var, num_features);
231 disparity_passed = (disp_avg < _zupt_max_disparity && num_features > 20);
232 if (disparity_passed) {
244 PRINT_DEBUG(
YELLOW "[ZUPT]: rejected |v_IinG| = %.3f (chi2 %.3f > %.3f)\n" RESET, state->_imu->vel().norm(), chi2,
248 PRINT_INFO(
CYAN "[ZUPT]: accepted |v_IinG| = %.3f (chi2 %.3f < %.3f)\n" RESET, state->_imu->vel().norm(), chi2,
263 if (!explicitly_enforce_zero_motion) {
267 if (model_time_varying_bias) {
268 Eigen::MatrixXd Phi_bias = Eigen::MatrixXd::Identity(6, 6);
269 std::vector<std::shared_ptr<Type>> Phi_order;
270 Phi_order.push_back(state->_imu->bg());
271 Phi_order.push_back(state->_imu->ba());
277 state->_timestamp = timestamp;
283 double time1_cam = timestamp;
284 _prop->propagate_and_clone(state, time1_cam);
287 H = Eigen::MatrixXd::Zero(9, 15);
288 res = Eigen::VectorXd::Zero(9);
289 R = Eigen::MatrixXd::Identity(9, 9);
292 Eigen::Matrix3d R_GtoI0 = state->_clones_IMU.at(time0_cam)->Rot();
293 Eigen::Vector3d p_I0inG = state->_clones_IMU.at(time0_cam)->pos();
294 Eigen::Matrix3d R_GtoI1 = state->_clones_IMU.at(time1_cam)->Rot();
295 Eigen::Vector3d p_I1inG = state->_clones_IMU.at(time1_cam)->pos();
296 res.block(0, 0, 3, 1) = -
log_so3(R_GtoI0 * R_GtoI1.transpose());
297 res.block(3, 0, 3, 1) = p_I1inG - p_I0inG;
298 res.block(6, 0, 3, 1) = state->_imu->vel();
303 Hx_order.push_back(state->_clones_IMU.at(time0_cam));
304 Hx_order.push_back(state->_clones_IMU.at(time1_cam));
305 Hx_order.push_back(state->_imu->v());
306 if (state->_options.do_fej) {
307 R_GtoI0 = state->_clones_IMU.at(time0_cam)->Rot_fej();
309 H.block(0, 0, 3, 3) = Eigen::Matrix3d::Identity();
310 H.block(0, 6, 3, 3) = -R_GtoI0;
311 H.block(3, 3, 3, 3) = -Eigen::Matrix3d::Identity();
312 H.block(3, 9, 3, 3) = Eigen::Matrix3d::Identity();
313 H.block(6, 12, 3, 3) = Eigen::Matrix3d::Identity();
316 R.block(0, 0, 3, 3) *= std::pow(1e-2, 2);
317 R.block(3, 3, 3, 3) *= std::pow(1e-1, 2);
318 R.block(6, 6, 3, 3) *= std::pow(1e-1, 2);
323 state->_clones_IMU.erase(time1_cam);