20 #include <boost/make_shared.hpp> 27 TangentPreintegration::TangentPreintegration(
const boost::shared_ptr<Params>&
p,
28 const Bias& biasHat) :
59 const auto theta = preintegrated.segment<3>(0);
60 const auto position = preintegrated.segment<3>(3);
61 const auto velocity = preintegrated.segment<3>(6);
68 Matrix3 w_tangent_H_theta, invH;
70 local.
applyInvDexp(w_body, A ? &w_tangent_H_theta : 0, C ? &invH : 0);
73 const double dt22 = 0.5 * dt *
dt;
75 Vector9 preintegratedPlus;
86 A->block<3, 3>(0, 0).noalias() += w_tangent_H_theta *
dt;
87 A->block<3, 3>(3, 0) = a_nav_H_theta * dt22;
88 A->block<3, 3>(3, 6) = I_3x3 * dt;
89 A->block<3, 3>(6, 0) = a_nav_H_theta * dt;
92 B->block<3, 3>(0, 0) = Z_3x3;
93 B->block<3, 3>(3, 0) =
R.matrix() * dt22;
94 B->block<3, 3>(6, 0) =
R.matrix() *
dt;
97 C->block<3, 3>(0, 0) = invH * dt;
98 C->block<3, 3>(3, 0) = Z_3x3;
99 C->block<3, 3>(6, 0) = Z_3x3;
102 return preintegratedPlus;
114 Matrix3 D_correctedAcc_acc, D_correctedAcc_omega, D_correctedOmega_omega;
115 if (
p().body_P_sensor)
117 D_correctedAcc_acc, D_correctedAcc_omega, D_correctedOmega_omega);
123 if (
p().body_P_sensor) {
125 *C *= D_correctedOmega_omega;
126 if (!
p().body_P_sensor->translation().isZero())
127 *C += *B * D_correctedAcc_omega;
128 *B *= D_correctedAcc_acc;
155 return biasCorrected;
160 #define D_R_R(H) (H)->block<3,3>(0,0) 161 #define D_R_t(H) (H)->block<3,3>(0,3) 162 #define D_R_v(H) (H)->block<3,3>(0,6) 163 #define D_t_R(H) (H)->block<3,3>(3,0) 164 #define D_t_t(H) (H)->block<3,3>(3,3) 165 #define D_t_v(H) (H)->block<3,3>(3,6) 166 #define D_v_R(H) (H)->block<3,3>(6,0) 167 #define D_v_t(H) (H)->block<3,3>(6,3) 168 #define D_v_v(H) (H)->block<3,3>(6,6) 174 const auto t01 = zeta01.segment<3>(0);
175 const auto p01 = zeta01.segment<3>(3);
176 const auto v01 = zeta01.segment<3>(6);
178 const auto t12 = zeta12.segment<3>(0);
179 const auto p12 = zeta12.segment<3>(3);
180 const auto v12 = zeta12.segment<3>(6);
182 Matrix3 R01_H_t01, R12_H_t12;
186 Matrix3 R02_H_R01, R02_H_R12;
187 const Rot3 R02 = R01.
compose(R12, R02_H_R01, R02_H_R12);
191 const Matrix3
R = R01.
matrix();
193 p01 + v01 * deltaT12 + R * p12,
198 D_R_R(H1) = t02_H_R02 * R02_H_R01 * R01_H_t01;
200 D_t_v(H1) = I_3x3 * deltaT12;
206 D_R_R(H2) = t02_H_R02 * R02_H_R12 * R12_H_t12;
218 throw std::domain_error(
219 "Cannot merge pre-integrated measurements with different params");
222 if (
params()->body_P_sensor) {
223 throw std::domain_error(
224 "Cannot merge pre-integrated measurements with sensor pose yet");
228 const double t12 = pim12.
deltaTij();
const imuBias::ConstantBias & biasHat() const
Vector9 biasCorrectedDelta(const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 6 > H=boost::none) const override
EIGEN_DEVICE_FUNC Derived & setZero(Index size)
static Vector9 Compose(const Vector9 &zeta01, const Vector9 &zeta12, double deltaT12, OptionalJacobian< 9, 9 > H1=boost::none, OptionalJacobian< 9, 9 > H2=boost::none)
Matrix93 preintegrated_H_biasAcc_
Jacobian of preintegrated_ w.r.t. acceleration bias.
Rot2 R(Rot2::fromAngle(0.1))
const Vector3 & accelerometer() const
boost::shared_ptr< Params > p_
Some functions to compute numerical derivatives.
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
Matrix93 preintegrated_H_biasOmega_
Jacobian of preintegrated_ w.r.t. angular rate bias.
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
bool equals(const TangentPreintegration &other, double tol) const
Class compose(const Class &g) const
SO3 expmap() const
Rodrigues formula.
static Vector9 UpdatePreintegrated(const Vector3 &a_body, const Vector3 &w_body, const double dt, const Vector9 &preintegrated, OptionalJacobian< 9, 9 > A=boost::none, OptionalJacobian< 9, 3 > B=boost::none, OptionalJacobian< 9, 3 > C=boost::none)
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)
const Vector9 & preintegrated() const
Velocity3_ velocity(const NavState_ &X)
const Matrix3 & dexp() const
void update(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt, Matrix9 *A, Matrix93 *B, Matrix93 *C) override
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
void mergeWith(const TangentPreintegration &pim, Matrix9 *H1, Matrix9 *H2)
Matrix3 skewSymmetric(double wx, double wy, double wz)
static const Vector3 measuredOmega(w, 0, 0)
static Vector3 Logmap(const Rot3 &R, OptionalJacobian< 3, 3 > H=boost::none)
Functor that implements Exponential map and its derivatives.
bool matchesParamsWith(const PreintegrationBase &other) const
check parameters equality: checks whether shared pointer points to same Params object.
Point3_ position(const NavState_ &X)
GTSAM_EXPORT Vector3 applyInvDexp(const Vector3 &v, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
Multiplies with dexp().inverse(), with optional derivatives.
const boost::shared_ptr< Params > & params() const
shared pointer to params
Vector3 correctGyroscope(const Vector3 &measurement, OptionalJacobian< 3, 6 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
void resetIntegration() override
Bias biasHat_
Acceleration and gyro bias used for preintegration.