GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
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,
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 }
virtual std::shared_ptr< TangentPreintegration > clone() const
Definition: TangentPreintegration.h:123
Definition: NavState.h:34
Definition: ImuBias.h:32
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:113
Vector9 preintegrated_
Definition: TangentPreintegration.h:35
Definition: PreintegrationBase.h:41
TangentPreintegration()
Default constructor for serialization.
Definition: TangentPreintegration.h:40
Matrix93 preintegrated_H_biasAcc_
Jacobian of preintegrated_ w.r.t. acceleration bias.
Definition: TangentPreintegration.h:36
Matrix93 preintegrated_H_biasOmega_
Jacobian of preintegrated_ w.r.t. angular rate bias.
Definition: TangentPreintegration.h:37
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H={})
Definition: Rot3.h:374
Definition: Testable.h:112
~TangentPreintegration() override
Virtual destructor.
Definition: TangentPreintegration.h:57
Definition: chartTesting.h:28
NavState retract(const Vector9 &v, OptionalJacobian< 9, 9 > H1={}, OptionalJacobian< 9, 9 > H2={}) const
retract with optional derivatives
Definition: OptionalJacobian.h:38
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:284
Definition: TangentPreintegration.h:28