Go to the documentation of this file.
29 ManifoldPreintegration::ManifoldPreintegration(
30 const std::shared_ptr<Params>&
p,
const Bias& biasHat) :
69 Matrix3 D_correctedAcc_acc, D_correctedAcc_omega, D_correctedOmega_omega;
72 acc,
omega, D_correctedAcc_acc, D_correctedAcc_omega,
73 D_correctedOmega_omega);
85 *
C *= D_correctedOmega_omega;
87 *
C += *
B * D_correctedAcc_omega;
88 *
B *= D_correctedAcc_acc;
94 oldRij.
rotate(acc, D_acc_R);
98 Matrix3 D_incrR_integratedOmega;
100 const Matrix3 incrRt = incrR.
transpose();
103 double dt22 = 0.5 *
dt *
dt;
104 const Matrix3 dRij = oldRij.
matrix();
116 Matrix3 D_correctedRij_bias;
119 H ? &D_correctedRij_bias : 0);
124 Matrix3 D_dR_correctedRij;
134 Matrix36 D_dR_bias, D_dP_bias, D_dV_bias;
135 D_dR_bias << Z_3x3, D_dR_correctedRij * D_correctedRij_bias;
138 (*H) << D_dR_bias, D_dP_bias, D_dV_bias;
void update(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt, Matrix9 *A, Matrix93 *B, Matrix93 *C) override
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
static Eigen::Block< Vector9, 3, 1 > dR(Vector9 &v)
Matrix3 delRdelBiasOmega_
Jacobian of preintegrated rotation w.r.t. angular rate bias.
const Vector3 & gyroscope() const
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
Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
static Eigen::Block< Vector9, 3, 1 > dP(Vector9 &v)
Rot3 deltaRij() const override
bool equals(const ConstantBias &expected, double tol=1e-5) const
std::pair< Vector3, Vector3 > correctMeasurementsBySensorPose(const Vector3 &unbiasedAcc, const Vector3 &unbiasedOmega, OptionalJacobian< 3, 3 > correctedAcc_H_unbiasedAcc={}, OptionalJacobian< 3, 3 > correctedAcc_H_unbiasedOmega={}, OptionalJacobian< 3, 3 > correctedOmega_H_unbiasedOmega={}) const
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Vector3 correctAccelerometer(const Vector3 &measurement, OptionalJacobian< 3, 6 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
Matrix3 delPdelBiasOmega_
Jacobian of preintegrated position w.r.t. angular rate bias.
static Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0))
Bias biasHat_
Acceleration and gyro bias used for preintegration.
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
const Vector3 measuredOmega
const Rot3 & attitude(OptionalJacobian< 3, 9 > H={}) const
Point3 rotate(const Point3 &p, OptionalJacobian< 3, 3 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
const Vector3 & accelerometer() const
Vector3 deltaVij() const override
Params & p() const
const reference to params
std::shared_ptr< Params > p_
static Eigen::Block< Vector9, 3, 1 > dV(Vector9 &v)
void resetIntegration() override
Matrix< Scalar, Dynamic, Dynamic > C
bool equals(const NavState &other, double tol=1e-8) const
equals
Matrix3 delPdelBiasAcc_
Jacobian of preintegrated position w.r.t. acceleration bias.
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H={})
double deltaTij_
Time interval from i to j.
Matrix3 delVdelBiasOmega_
Jacobian of preintegrated velocity w.r.t. angular rate bias.
Matrix3 transpose() const
static Vector3 Logmap(const Rot3 &R, OptionalJacobian< 3, 3 > H={})
static const Vector3 measuredAcc
Vector3 deltaPij() const override
Vector3 correctGyroscope(const Vector3 &measurement, OptionalJacobian< 3, 6 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
Matrix3 delVdelBiasAcc_
Jacobian of preintegrated velocity w.r.t. acceleration bias.
Class expmap(const TangentVector &v) const
Vector9 biasCorrectedDelta(const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 6 > H={}) const override
bool equals(const ManifoldPreintegration &other, double tol) const
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:02:45