ManifoldPreintegration.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
22 #include "ManifoldPreintegration.h"
23 
24 using namespace std;
25 
26 namespace gtsam {
27 
28 //------------------------------------------------------------------------------
29 ManifoldPreintegration::ManifoldPreintegration(
30  const boost::shared_ptr<Params>& p, const Bias& biasHat) :
31  PreintegrationBase(p, biasHat) {
33 }
34 
35 //------------------------------------------------------------------------------
37  deltaTij_ = 0.0;
38  deltaXij_ = NavState();
39  delRdelBiasOmega_.setZero();
40  delPdelBiasAcc_.setZero();
41  delPdelBiasOmega_.setZero();
42  delVdelBiasAcc_.setZero();
43  delVdelBiasOmega_.setZero();
44 }
45 
46 //------------------------------------------------------------------------------
48  double tol) const {
49  return p_->equals(*other.p_, tol) && std::abs(deltaTij_ - other.deltaTij_) < tol
50  && biasHat_.equals(other.biasHat_, tol)
51  && deltaXij_.equals(other.deltaXij_, tol)
57 }
58 
59 //------------------------------------------------------------------------------
61  const Vector3& measuredOmega, const double dt, Matrix9* A, Matrix93* B,
62  Matrix93* C) {
63 
64  // Correct for bias in the sensor frame
65  Vector3 acc = biasHat_.correctAccelerometer(measuredAcc);
66  Vector3 omega = biasHat_.correctGyroscope(measuredOmega);
67 
68  // Possibly correct for sensor pose
69  Matrix3 D_correctedAcc_acc, D_correctedAcc_omega, D_correctedOmega_omega;
70  if (p().body_P_sensor)
71  boost::tie(acc, omega) = correctMeasurementsBySensorPose(acc, omega,
72  D_correctedAcc_acc, D_correctedAcc_omega, D_correctedOmega_omega);
73 
74  // Save current rotation for updating Jacobians
75  const Rot3 oldRij = deltaXij_.attitude();
76 
77  // Do update
78  deltaTij_ += dt;
79  deltaXij_ = deltaXij_.update(acc, omega, dt, A, B, C); // functional
80 
81  if (p().body_P_sensor) {
82  // More complicated derivatives in case of non-trivial sensor pose
83  *C *= D_correctedOmega_omega;
84  if (!p().body_P_sensor->translation().isZero())
85  *C += *B * D_correctedAcc_omega;
86  *B *= D_correctedAcc_acc; // NOTE(frank): needs to be last
87  }
88 
89  // Update Jacobians
90  // TODO(frank): Try same simplification as in new approach
91  Matrix3 D_acc_R;
92  oldRij.rotate(acc, D_acc_R);
93  const Matrix3 D_acc_biasOmega = D_acc_R * delRdelBiasOmega_;
94 
95  const Vector3 integratedOmega = omega * dt;
96  Matrix3 D_incrR_integratedOmega;
97  const Rot3 incrR = Rot3::Expmap(integratedOmega, D_incrR_integratedOmega); // expensive !!
98  const Matrix3 incrRt = incrR.transpose();
99  delRdelBiasOmega_ = incrRt * delRdelBiasOmega_ - D_incrR_integratedOmega * dt;
100 
101  double dt22 = 0.5 * dt * dt;
102  const Matrix3 dRij = oldRij.matrix(); // expensive
103  delPdelBiasAcc_ += delVdelBiasAcc_ * dt - dt22 * dRij;
104  delPdelBiasOmega_ += dt * delVdelBiasOmega_ + dt22 * D_acc_biasOmega;
105  delVdelBiasAcc_ += -dRij * dt;
106  delVdelBiasOmega_ += D_acc_biasOmega * dt;
107 }
108 
109 //------------------------------------------------------------------------------
111  const imuBias::ConstantBias& bias_i, OptionalJacobian<9, 6> H) const {
112  // Correct deltaRij, derivative is delRdelBiasOmega_
113  const imuBias::ConstantBias biasIncr = bias_i - biasHat_;
114  Matrix3 D_correctedRij_bias;
115  const Vector3 biasInducedOmega = delRdelBiasOmega_ * biasIncr.gyroscope();
116  const Rot3 correctedRij = deltaRij().expmap(biasInducedOmega, boost::none,
117  H ? &D_correctedRij_bias : 0);
118  if (H)
119  D_correctedRij_bias *= delRdelBiasOmega_;
120 
121  Vector9 xi;
122  Matrix3 D_dR_correctedRij;
123  // TODO(frank): could line below be simplified? It is equivalent to
124  // LogMap(deltaRij_.compose(Expmap(biasInducedOmega)))
125  NavState::dR(xi) = Rot3::Logmap(correctedRij, H ? &D_dR_correctedRij : 0);
126  NavState::dP(xi) = deltaPij() + delPdelBiasAcc_ * biasIncr.accelerometer()
127  + delPdelBiasOmega_ * biasIncr.gyroscope();
128  NavState::dV(xi) = deltaVij() + delVdelBiasAcc_ * biasIncr.accelerometer()
129  + delVdelBiasOmega_ * biasIncr.gyroscope();
130 
131  if (H) {
132  Matrix36 D_dR_bias, D_dP_bias, D_dV_bias;
133  D_dR_bias << Z_3x3, D_dR_correctedRij * D_correctedRij_bias;
134  D_dP_bias << delPdelBiasAcc_, delPdelBiasOmega_;
135  D_dV_bias << delVdelBiasAcc_, delVdelBiasOmega_;
136  (*H) << D_dR_bias, D_dP_bias, D_dV_bias;
137  }
138  return xi;
139 }
140 
141 //------------------------------------------------------------------------------
142 
143 }// namespace gtsam
Eigen::Vector3d Vector3
Definition: Vector.h:43
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
Definition: ImuBias.h:59
boost::shared_ptr< Params > p_
Matrix3 delRdelBiasOmega_
Jacobian of preintegrated rotation w.r.t. angular rate bias.
Definition: Half.h:150
static Eigen::Block< Vector9, 3, 1 > dP(Vector9 &v)
Definition: NavState.h:141
Matrix3 matrix() const
Definition: Rot3M.cpp:219
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
Definition: Rot3M.cpp:149
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.
const double dt
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
Definition: Lie.h:77
static Eigen::Block< Vector9, 3, 1 > dV(Vector9 &v)
Definition: NavState.h:144
Vector3 correctAccelerometer(const Vector3 &measurement, OptionalJacobian< 3, 6 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
Definition: ImuBias.h:69
Params & p() const
const reference to params
bool equals(const ConstantBias &expected, double tol=1e-5) const
Definition: ImuBias.h:98
static const Vector3 measuredAcc
double deltaTij_
Time interval from i to j.
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H=boost::none)
Definition: Rot3.h:377
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
Definition: NavState.cpp:171
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Definition: base/Matrix.h:84
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:37
const Vector3 & gyroscope() const
Definition: ImuBias.h:64
Vector xi
Definition: testPose2.cpp:150
Matrix3 transpose() const
Definition: Rot3M.cpp:144
traits
Definition: chartTesting.h:28
static const Vector3 measuredOmega(w, 0, 0)
static Vector3 Logmap(const Rot3 &R, OptionalJacobian< 3, 3 > H=boost::none)
Definition: Rot3M.cpp:158
float * p
Vector3 correctGyroscope(const Vector3 &measurement, OptionalJacobian< 3, 6 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
Definition: ImuBias.h:78
const G double tol
Definition: Group.h:83
#define abs(x)
Definition: datatypes.h:17
bool equals(const NavState &other, double tol=1e-8) const
equals
Definition: NavState.cpp:103
Bias biasHat_
Acceleration and gyro bias used for preintegration.
static Eigen::Block< Vector9, 3, 1 > dR(Vector9 &v)
Definition: NavState.h:138
const Rot3 & attitude(OptionalJacobian< 3, 9 > H=boost::none) const
Definition: NavState.cpp:50


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:35