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 boost::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,
94  OptionalJacobian<9, 9> A = boost::none,
95  OptionalJacobian<9, 3> B = boost::none,
96  OptionalJacobian<9, 3> C = boost::none);
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 = boost::none) 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 = boost::none,
115  OptionalJacobian<9, 9> H2 = boost::none);
116 
119  void mergeWith(const TangentPreintegration& pim, Matrix9* H1, Matrix9* H2);
121 
123  virtual boost::shared_ptr<TangentPreintegration> clone() const {
124  return boost::shared_ptr<TangentPreintegration>();
125  }
126 
128 
129 private:
131  friend class boost::serialization::access;
132  template<class ARCHIVE>
133  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
134  namespace bs = ::boost::serialization;
135  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationBase);
136  ar & BOOST_SERIALIZATION_NVP(preintegrated_);
137  ar & BOOST_SERIALIZATION_NVP(preintegrated_H_biasAcc_);
138  ar & BOOST_SERIALIZATION_NVP(preintegrated_H_biasOmega_);
139  }
140 
141 public:
143 };
144 
145 }
Vector3 deltaPij() const override
NavState deltaXij() const override
def update(text)
Definition: relicense.py:46
Eigen::Vector3d Vector3
Definition: Vector.h:43
TangentPreintegration()
Default constructor for serialization.
Matrix93 preintegrated_H_biasAcc_
Jacobian of preintegrated_ w.r.t. acceleration bias.
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
Rot2 theta
Matrix93 preintegrated_H_biasOmega_
Jacobian of preintegrated_ w.r.t. angular rate bias.
const Matrix93 & preintegrated_H_biasOmega() const
const double dt
virtual boost::shared_ptr< TangentPreintegration > clone() const
NavState retract(const Vector9 &v, OptionalJacobian< 9, 9 > H1=boost::none, OptionalJacobian< 9, 9 > H2=boost::none) const
retract with optional derivatives
Definition: NavState.cpp:109
~TangentPreintegration() override
Virtual destructor.
void serialize(ARCHIVE &ar, const unsigned int)
static const Vector3 measuredAcc
const Matrix93 & preintegrated_H_biasAcc() const
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H=boost::none)
Definition: Rot3.h:377
const Vector9 & preintegrated() const
Vector3 deltaVij() const override
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:37
traits
Definition: chartTesting.h:28
static const Vector3 measuredOmega(w, 0, 0)
float * p
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:269
const G double tol
Definition: Group.h:83


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:45:07