TangentPreintegration.h
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 
18 #pragma once
19 
21 
22 namespace gtsam {
23 
28 class GTSAM_EXPORT TangentPreintegration : public PreintegrationBase {
29  protected:
30 
35  Vector9 preintegrated_;
38 
41  resetIntegration();
42  }
43 
44 public:
47 
53  TangentPreintegration(const std::shared_ptr<Params>& p,
54  const imuBias::ConstantBias& biasHat = imuBias::ConstantBias());
55 
58  }
59 
61 
65  void resetIntegration() override;
66 
68 
71  Vector3 deltaPij() const override { return preintegrated_.segment<3>(3); }
72  Vector3 deltaVij() const override { return preintegrated_.tail<3>(); }
73  Rot3 deltaRij() const override { return Rot3::Expmap(theta()); }
74  NavState deltaXij() const override { return NavState().retract(preintegrated_); }
75 
76  const Vector9& preintegrated() const { return preintegrated_; }
77  Vector3 theta() const { return preintegrated_.head<3>(); }
78  const Matrix93& preintegrated_H_biasAcc() const { return preintegrated_H_biasAcc_; }
79  const Matrix93& preintegrated_H_biasOmega() const { return preintegrated_H_biasOmega_; }
80 
83  bool equals(const TangentPreintegration& other, double tol) const;
85 
88 
89  // Update integrated vector on tangent manifold preintegrated with acceleration
90  // Static, functional version.
91  static Vector9 UpdatePreintegrated(const Vector3& a_body,
92  const Vector3& w_body, const double dt,
93  const Vector9& preintegrated,
95  OptionalJacobian<9, 3> B = {},
96  OptionalJacobian<9, 3> C = {});
97 
102  void update(const Vector3& measuredAcc, const Vector3& measuredOmega,
103  const double dt, Matrix9* A, Matrix93* B, Matrix93* C) override;
104 
108  Vector9 biasCorrectedDelta(const imuBias::ConstantBias& bias_i,
109  OptionalJacobian<9, 6> H = {}) const override;
110 
111  // Compose the two pre-integrated 9D-vectors zeta01 and zeta02, with derivatives
112  static Vector9 Compose(const Vector9& zeta01, const Vector9& zeta12,
113  double deltaT12,
114  OptionalJacobian<9, 9> H1 = {},
115  OptionalJacobian<9, 9> H2 = {});
116 
119  void mergeWith(const TangentPreintegration& pim, Matrix9* H1, Matrix9* H2);
121 
123  virtual std::shared_ptr<TangentPreintegration> clone() const {
124  return std::shared_ptr<TangentPreintegration>();
125  }
126 
128 
129 private:
130 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
131 
132  friend class boost::serialization::access;
133  template<class ARCHIVE>
134  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
135  namespace bs = ::boost::serialization;
136  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationBase);
137  ar & BOOST_SERIALIZATION_NVP(preintegrated_);
138  ar & BOOST_SERIALIZATION_NVP(preintegrated_H_biasAcc_);
139  ar & BOOST_SERIALIZATION_NVP(preintegrated_H_biasOmega_);
140  }
141 #endif
142 
143 public:
145 };
146 
147 }
H
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
Definition: gnuplot_common_settings.hh:74
relicense.update
def update(text)
Definition: relicense.py:46
gtsam::TangentPreintegration::preintegrated_H_biasOmega_
Matrix93 preintegrated_H_biasOmega_
Jacobian of preintegrated_ w.r.t. angular rate bias.
Definition: TangentPreintegration.h:37
gtsam::TangentPreintegration::deltaXij
NavState deltaXij() const override
Definition: TangentPreintegration.h:74
gtsam::TangentPreintegration::deltaPij
Vector3 deltaPij() const override
Definition: TangentPreintegration.h:71
PreintegrationBase.h
gtsam::TangentPreintegration::deltaRij
Rot3 deltaRij() const override
Definition: TangentPreintegration.h:73
B
Definition: test_numpy_dtypes.cpp:299
dt
const double dt
Definition: testVelocityConstraint.cpp:15
gtsam::PreintegrationBase
Definition: PreintegrationBase.h:41
gtsam::NavState
Definition: NavState.h:38
gtsam::TangentPreintegration::theta
Vector3 theta() const
Definition: TangentPreintegration.h:77
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
gtsam::TangentPreintegration::preintegrated
const Vector9 & preintegrated() const
Definition: TangentPreintegration.h:76
gtsam::TangentPreintegration::TangentPreintegration
TangentPreintegration()
Default constructor for serialization.
Definition: TangentPreintegration.h:40
A
Definition: test_numpy_dtypes.cpp:298
biased_x_rotation::measuredOmega
const Vector3 measuredOmega
Definition: testPreintegratedRotation.cpp:35
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::TangentPreintegration::preintegrated_H_biasAcc_
Matrix93 preintegrated_H_biasAcc_
Jacobian of preintegrated_ w.r.t. acceleration bias.
Definition: TangentPreintegration.h:36
gtsam::TangentPreintegration::preintegrated_
Vector9 preintegrated_
Definition: TangentPreintegration.h:35
gtsam::TangentPreintegration::clone
virtual std::shared_ptr< TangentPreintegration > clone() const
Definition: TangentPreintegration.h:123
gtsam::TangentPreintegration::preintegrated_H_biasAcc
const Matrix93 & preintegrated_H_biasAcc() const
Definition: TangentPreintegration.h:78
gtsam::equals
Definition: Testable.h:112
gtsam::imuBias::ConstantBias
Definition: ImuBias.h:32
C
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:50
gtsam
traits
Definition: SFMdata.h:40
gtsam::TangentPreintegration
Definition: TangentPreintegration.h:28
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
gtsam::Rot3::Expmap
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H={})
Definition: Rot3.h:378
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::TangentPreintegration::deltaVij
Vector3 deltaVij() const override
Definition: TangentPreintegration.h:72
gtsam::NavState::retract
NavState retract(const Vector9 &v, OptionalJacobian< 9, 9 > H1={}, OptionalJacobian< 9, 9 > H2={}) const
retract with optional derivatives
Definition: NavState.cpp:264
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::TangentPreintegration::preintegrated_H_biasOmega
const Matrix93 & preintegrated_H_biasOmega() const
Definition: TangentPreintegration.h:79
gtsam::TangentPreintegration::~TangentPreintegration
~TangentPreintegration() override
Virtual destructor.
Definition: TangentPreintegration.h:57
common::measuredAcc
static const Vector3 measuredAcc
Definition: testImuFactor.cpp:181
Eigen::Matrix< double, 9, 3 >
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:279
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:14:23