ImuFactor.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 
22 #pragma once
23 
24 /* GTSAM includes */
28 #include <gtsam/base/debug.h>
29 
30 namespace gtsam {
31 
32 #ifdef GTSAM_TANGENT_PREINTEGRATION
33 typedef TangentPreintegration PreintegrationType;
34 #else
35 typedef ManifoldPreintegration PreintegrationType;
36 #endif
37 
38 /*
39  * If you are using the factor, please cite:
40  * L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert, "Eliminating
41  * conditionally independent sets in factor graphs: a unifying perspective based
42  * on smart factors", Int. Conf. on Robotics and Automation (ICRA), 2014.
43  *
44  * C. Forster, L. Carlone, F. Dellaert, D. Scaramuzza, "IMU Preintegration on
45  * Manifold for Efficient Visual-Inertial Maximum-a-Posteriori Estimation",
46  * Robotics: Science and Systems (RSS), 2015.
47  *
48  * REFERENCES:
49  * [1] G.S. Chirikjian, "Stochastic Models, Information Theory, and Lie Groups",
50  * Volume 2, 2008.
51  * [2] T. Lupton and S.Sukkarieh, "Visual-Inertial-Aided Navigation for
52  * High-Dynamic Motion in Built Environments Without Initial Conditions",
53  * TRO, 28(1):61-76, 2012.
54  * [3] L. Carlone, S. Williams, R. Roberts, "Preintegrated IMU factor:
55  * Computation of the Jacobian Matrices", Tech. Report, 2013.
56  * [4] C. Forster, L. Carlone, F. Dellaert, D. Scaramuzza, "IMU Preintegration on
57  * Manifold for Efficient Visual-Inertial Maximum-a-Posteriori Estimation",
58  * Robotics: Science and Systems (RSS), 2015.
59  */
60 
71 class GTSAM_EXPORT PreintegratedImuMeasurements: public PreintegrationType {
72 
73  friend class ImuFactor;
74  friend class ImuFactor2;
75 
76 protected:
77 
79 
81 public:
82 
85  preintMeasCov_.setZero();
86  }
87 
93  PreintegratedImuMeasurements(const boost::shared_ptr<PreintegrationParams>& p,
94  const imuBias::ConstantBias& biasHat = imuBias::ConstantBias()) :
95  PreintegrationType(p, biasHat) {
96  preintMeasCov_.setZero();
97  }
98 
104  PreintegratedImuMeasurements(const PreintegrationType& base, const Matrix9& preintMeasCov)
105  : PreintegrationType(base),
106  preintMeasCov_(preintMeasCov) {
107  }
108 
111  }
112 
114  void print(const std::string& s = "Preintegrated Measurements:") const override;
115 
117  bool equals(const PreintegratedImuMeasurements& expected, double tol = 1e-9) const;
118 
120  void resetIntegration() override;
121 
128  void integrateMeasurement(const Vector3& measuredAcc,
129  const Vector3& measuredOmega, const double dt) override;
130 
132  void integrateMeasurements(const Matrix& measuredAccs, const Matrix& measuredOmegas,
133  const Matrix& dts);
134 
136  Matrix preintMeasCov() const { return preintMeasCov_; }
137 
138 #ifdef GTSAM_TANGENT_PREINTEGRATION
139  void mergeWith(const PreintegratedImuMeasurements& pim, Matrix9* H1, Matrix9* H2);
141 #endif
142 
143  private:
145  friend class boost::serialization::access;
146  template<class ARCHIVE>
147  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
148  namespace bs = ::boost::serialization;
149  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationType);
150  ar & BOOST_SERIALIZATION_NVP(preintMeasCov_);
151  }
152 };
153 
166 class GTSAM_EXPORT ImuFactor: public NoiseModelFactor5<Pose3, Vector3, Pose3, Vector3,
167  imuBias::ConstantBias> {
168 private:
169 
170  typedef ImuFactor This;
171  typedef NoiseModelFactor5<Pose3, Vector3, Pose3, Vector3,
173 
175 
176 public:
177 
179 #if !defined(_MSC_VER) && __GNUC__ == 4 && __GNUC_MINOR__ > 5
180  typedef typename boost::shared_ptr<ImuFactor> shared_ptr;
181 #else
182  typedef boost::shared_ptr<ImuFactor> shared_ptr;
183 #endif
184 
187 
198  ImuFactor(Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias,
199  const PreintegratedImuMeasurements& preintegratedMeasurements);
200 
201  ~ImuFactor() override {
202  }
203 
205  gtsam::NonlinearFactor::shared_ptr clone() const override;
206 
209  GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os, const ImuFactor&);
210  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
211  DefaultKeyFormatter) const override;
212  bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;
214 
218  return _PIM_;
219  }
220 
223  Vector evaluateError(const Pose3& pose_i, const Vector3& vel_i,
225  const Pose3& pose_j, const Vector3& vel_j,
226  const imuBias::ConstantBias& bias_i, boost::optional<Matrix&> H1 =
227  boost::none, boost::optional<Matrix&> H2 = boost::none,
228  boost::optional<Matrix&> H3 = boost::none, boost::optional<Matrix&> H4 =
229  boost::none, boost::optional<Matrix&> H5 = boost::none) const override;
230 
231 #ifdef GTSAM_TANGENT_PREINTEGRATION
232  static PreintegratedImuMeasurements Merge(
234  const PreintegratedImuMeasurements& pim01,
235  const PreintegratedImuMeasurements& pim12);
236 
238  static shared_ptr Merge(const shared_ptr& f01, const shared_ptr& f12);
239 #endif
240 
241  private:
243  friend class boost::serialization::access;
244  template<class ARCHIVE>
245  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
246  ar & boost::serialization::make_nvp("NoiseModelFactor5",
247  boost::serialization::base_object<Base>(*this));
248  ar & BOOST_SERIALIZATION_NVP(_PIM_);
249  }
250 };
251 // class ImuFactor
252 
257 class GTSAM_EXPORT ImuFactor2 : public NoiseModelFactor3<NavState, NavState, imuBias::ConstantBias> {
258 private:
259 
260  typedef ImuFactor2 This;
262 
264 
265 public:
266 
269 
276  ImuFactor2(Key state_i, Key state_j, Key bias,
277  const PreintegratedImuMeasurements& preintegratedMeasurements);
278 
279  ~ImuFactor2() override {
280  }
281 
283  gtsam::NonlinearFactor::shared_ptr clone() const override;
284 
287  GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os, const ImuFactor2&);
288  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
289  DefaultKeyFormatter) const override;
290  bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;
292 
296  return _PIM_;
297  }
298 
301  Vector evaluateError(const NavState& state_i, const NavState& state_j,
303  const imuBias::ConstantBias& bias_i, //
304  boost::optional<Matrix&> H1 = boost::none,
305  boost::optional<Matrix&> H2 = boost::none,
306  boost::optional<Matrix&> H3 = boost::none) const override;
307 
308 private:
309 
311  friend class boost::serialization::access;
312  template<class ARCHIVE>
313  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
314  ar & boost::serialization::make_nvp("NoiseModelFactor3",
315  boost::serialization::base_object<Base>(*this));
316  ar & BOOST_SERIALIZATION_NVP(_PIM_);
317  }
318 };
319 // class ImuFactor2
320 
321 template <>
322 struct traits<PreintegratedImuMeasurements> : public Testable<PreintegratedImuMeasurements> {};
323 
324 template <>
325 struct traits<ImuFactor> : public Testable<ImuFactor> {};
326 
327 template <>
328 struct traits<ImuFactor2> : public Testable<ImuFactor2> {};
329 
330 }
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
EIGEN_DEVICE_FUNC Derived & setZero(Index size)
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Definition: testGroup.cpp:109
Eigen::Vector3d Vector3
Definition: Vector.h:43
Global debugging flags.
Matrix expected
Definition: testMatrix.cpp:974
~PreintegratedImuMeasurements() override
Virtual destructor.
Definition: ImuFactor.h:110
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
void integrateMeasurements(const vector< ImuMeasurement > &measurements, PIM *pim)
~ImuFactor() override
Definition: ImuFactor.h:201
void serialize(ARCHIVE &ar, const unsigned int)
Definition: ImuFactor.h:313
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
ImuFactor This
Definition: ImuFactor.h:170
const double dt
PreintegratedImuMeasurements _PIM_
Definition: ImuFactor.h:174
Eigen::VectorXd Vector
Definition: Vector.h:38
PreintegratedImuMeasurements _PIM_
Definition: ImuFactor.h:263
ManifoldPreintegration PreintegrationType
PreintegratedImuMeasurements()
Default constructor for serialization and wrappers.
Definition: ImuFactor.h:84
boost::shared_ptr< This > shared_ptr
Matrix preintMeasCov() const
Return pre-integrated measurement covariance.
Definition: ImuFactor.h:136
boost::shared_ptr< ImuFactor > shared_ptr
Definition: ImuFactor.h:182
NoiseModelFactor3< NavState, NavState, imuBias::ConstantBias > Base
Definition: ImuFactor.h:261
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
Matrix9 preintMeasCov_
(first-order propagation from measurementCovariance).
Definition: ImuFactor.h:78
static const Vector3 measuredAcc
Point3 bias(10,-10, 50)
ImuFactor2 This
Definition: ImuFactor.h:260
traits
Definition: chartTesting.h:28
NoiseModelFactor5< Pose3, Vector3, Pose3, Vector3, imuBias::ConstantBias > Base
Definition: ImuFactor.h:172
static const Vector3 measuredOmega(w, 0, 0)
boost::shared_ptr< Factor > shared_ptr
A shared_ptr to this class.
Definition: Factor.h:60
void serialize(ARCHIVE &ar, const unsigned int)
Definition: ImuFactor.h:147
Non-linear factor base classes.
ofstream os("timeSchurFactors.csv")
const PreintegratedImuMeasurements & preintegratedMeasurements() const
Definition: ImuFactor.h:295
void serialize(ARCHIVE &ar, const unsigned int)
Definition: ImuFactor.h:245
float * p
const PreintegratedImuMeasurements & preintegratedMeasurements() const
Definition: ImuFactor.h:217
~ImuFactor2() override
Definition: ImuFactor.h:279
PreintegratedImuMeasurements(const boost::shared_ptr< PreintegrationParams > &p, const imuBias::ConstantBias &biasHat=imuBias::ConstantBias())
Definition: ImuFactor.h:93
PreintegratedImuMeasurements(const PreintegrationType &base, const Matrix9 &preintMeasCov)
Definition: ImuFactor.h:104
const G double tol
Definition: Group.h:83
Annotation indicating that a class derives from another given type.
Definition: attr.h:42
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61


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