29 ManifoldPreintegration::ManifoldPreintegration(
30 const boost::shared_ptr<Params>&
p,
const Bias& biasHat) :
69 Matrix3 D_correctedAcc_acc, D_correctedAcc_omega, D_correctedOmega_omega;
70 if (
p().body_P_sensor)
72 D_correctedAcc_acc, D_correctedAcc_omega, D_correctedOmega_omega);
81 if (
p().body_P_sensor) {
83 *C *= D_correctedOmega_omega;
84 if (!
p().body_P_sensor->translation().isZero())
85 *C += *B * D_correctedAcc_omega;
86 *B *= D_correctedAcc_acc;
92 oldRij.
rotate(acc, D_acc_R);
95 const Vector3 integratedOmega = omega *
dt;
96 Matrix3 D_incrR_integratedOmega;
99 delRdelBiasOmega_ = incrRt * delRdelBiasOmega_ - D_incrR_integratedOmega *
dt;
101 double dt22 = 0.5 * dt *
dt;
102 const Matrix3 dRij = oldRij.
matrix();
114 Matrix3 D_correctedRij_bias;
117 H ? &D_correctedRij_bias : 0);
122 Matrix3 D_dR_correctedRij;
132 Matrix36 D_dR_bias, D_dP_bias, D_dV_bias;
133 D_dR_bias << Z_3x3, D_dR_correctedRij * D_correctedRij_bias;
136 (*H) << D_dR_bias, D_dP_bias, D_dV_bias;
Vector9 biasCorrectedDelta(const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 6 > H=boost::none) const override
Matrix3 delPdelBiasAcc_
Jacobian of preintegrated position w.r.t. acceleration bias.
const Vector3 & accelerometer() const
boost::shared_ptr< Params > p_
Matrix3 delRdelBiasOmega_
Jacobian of preintegrated rotation w.r.t. angular rate bias.
static Eigen::Block< Vector9, 3, 1 > dP(Vector9 &v)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
Point3 rotate(const Point3 &p, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
void resetIntegration() override
Matrix3 delPdelBiasOmega_
Jacobian of preintegrated position w.r.t. angular rate bias.
bool equals(const ManifoldPreintegration &other, double tol) const
std::pair< Vector3, Vector3 > correctMeasurementsBySensorPose(const Vector3 &unbiasedAcc, const Vector3 &unbiasedOmega, OptionalJacobian< 3, 3 > correctedAcc_H_unbiasedAcc=boost::none, OptionalJacobian< 3, 3 > correctedAcc_H_unbiasedOmega=boost::none, OptionalJacobian< 3, 3 > correctedOmega_H_unbiasedOmega=boost::none) const
Matrix3 delVdelBiasOmega_
Jacobian of preintegrated velocity w.r.t. angular rate bias.
void update(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt, Matrix9 *A, Matrix93 *B, Matrix93 *C) override
Vector3 deltaPij() const override
Matrix3 delVdelBiasAcc_
Jacobian of preintegrated velocity w.r.t. acceleration bias.
Vector3 deltaVij() const override
Class expmap(const TangentVector &v) const
static Eigen::Block< Vector9, 3, 1 > dV(Vector9 &v)
Vector3 correctAccelerometer(const Vector3 &measurement, OptionalJacobian< 3, 6 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
Params & p() const
const reference to params
bool equals(const ConstantBias &expected, double tol=1e-5) const
static const Vector3 measuredAcc
double deltaTij_
Time interval from i to j.
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H=boost::none)
NavState update(const Vector3 &b_acceleration, const Vector3 &b_omega, const double dt, OptionalJacobian< 9, 9 > F, OptionalJacobian< 9, 3 > G1, OptionalJacobian< 9, 3 > G2) const
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Matrix< Scalar, Dynamic, Dynamic > C
const Vector3 & gyroscope() const
Matrix3 transpose() const
static const Vector3 measuredOmega(w, 0, 0)
static Vector3 Logmap(const Rot3 &R, OptionalJacobian< 3, 3 > H=boost::none)
Rot3 deltaRij() const override
Vector3 correctGyroscope(const Vector3 &measurement, OptionalJacobian< 3, 6 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
bool equals(const NavState &other, double tol=1e-8) const
equals
Bias biasHat_
Acceleration and gyro bias used for preintegration.
static Eigen::Block< Vector9, 3, 1 > dR(Vector9 &v)
const Rot3 & attitude(OptionalJacobian< 3, 9 > H=boost::none) const