gtsam  4.0.0
gtsam
ImuFactor.h
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 
72 
73  friend class ImuFactor;
74  friend class ImuFactor2;
75 
76 protected:
77 
78  Matrix9 preintMeasCov_;
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 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4
147  const Matrix3& measuredAccCovariance,
148  const Matrix3& measuredOmegaCovariance,
149  const Matrix3& integrationErrorCovariance,
150  bool use2ndOrderIntegration = true);
151 
154  void integrateMeasurement(const Vector3& measuredAcc,
155  const Vector3& measuredOmega, double dt,
156  boost::optional<Pose3> body_P_sensor);
157 #endif
158 
159 private:
160 
162  friend class boost::serialization::access;
163  template<class ARCHIVE>
164  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
165  namespace bs = ::boost::serialization;
166  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationType);
167  ar & bs::make_nvp("preintMeasCov_", bs::make_array(preintMeasCov_.data(), preintMeasCov_.size()));
168  }
169 };
170 
183 class GTSAM_EXPORT ImuFactor: public NoiseModelFactor5<Pose3, Vector3, Pose3, Vector3,
184  imuBias::ConstantBias> {
185 private:
186 
187  typedef ImuFactor This;
188  typedef NoiseModelFactor5<Pose3, Vector3, Pose3, Vector3,
190 
192 
193 public:
194 
196 #if !defined(_MSC_VER) && __GNUC__ == 4 && __GNUC_MINOR__ > 5
197  typedef typename boost::shared_ptr<ImuFactor> shared_ptr;
198 #else
199  typedef boost::shared_ptr<ImuFactor> shared_ptr;
200 #endif
201 
204 
213  ImuFactor(Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias,
214  const PreintegratedImuMeasurements& preintegratedMeasurements);
215 
216  virtual ~ImuFactor() {
217  }
218 
220  virtual gtsam::NonlinearFactor::shared_ptr clone() const;
221 
224  GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os, const ImuFactor&);
225  virtual void print(const std::string& s, const KeyFormatter& keyFormatter =
226  DefaultKeyFormatter) const;
227  virtual bool equals(const NonlinearFactor& expected, double tol = 1e-9) const;
229 
233  return _PIM_;
234  }
235 
238  Vector evaluateError(const Pose3& pose_i, const Vector3& vel_i,
240  const Pose3& pose_j, const Vector3& vel_j,
241  const imuBias::ConstantBias& bias_i, boost::optional<Matrix&> H1 =
242  boost::none, boost::optional<Matrix&> H2 = boost::none,
243  boost::optional<Matrix&> H3 = boost::none, boost::optional<Matrix&> H4 =
244  boost::none, boost::optional<Matrix&> H5 = boost::none) const;
245 
246 #ifdef GTSAM_TANGENT_PREINTEGRATION
247  static PreintegratedImuMeasurements Merge(
249  const PreintegratedImuMeasurements& pim01,
250  const PreintegratedImuMeasurements& pim12);
251 
253  static shared_ptr Merge(const shared_ptr& f01, const shared_ptr& f12);
254 #endif
255 
256 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4
257  typedef PreintegratedImuMeasurements PreintegratedMeasurements;
259 
261  ImuFactor(Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias,
262  const PreintegratedMeasurements& preintegratedMeasurements,
263  const Vector3& n_gravity, const Vector3& omegaCoriolis,
264  const boost::optional<Pose3>& body_P_sensor = boost::none,
265  const bool use2ndOrderCoriolis = false);
266 
269  static void Predict(const Pose3& pose_i, const Vector3& vel_i, Pose3& pose_j,
270  Vector3& vel_j, const imuBias::ConstantBias& bias_i,
271  PreintegratedMeasurements& pim, const Vector3& n_gravity,
272  const Vector3& omegaCoriolis, const bool use2ndOrderCoriolis = false);
273 #endif
274 
275 private:
276 
278  friend class boost::serialization::access;
279  template<class ARCHIVE>
280  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
281  ar & boost::serialization::make_nvp("NoiseModelFactor5",
282  boost::serialization::base_object<Base>(*this));
283  ar & BOOST_SERIALIZATION_NVP(_PIM_);
284  }
285 };
286 // class ImuFactor
287 
292 class GTSAM_EXPORT ImuFactor2 : public NoiseModelFactor3<NavState, NavState, imuBias::ConstantBias> {
293 private:
294 
295  typedef ImuFactor2 This;
297 
299 
300 public:
301 
304 
311  ImuFactor2(Key state_i, Key state_j, Key bias,
312  const PreintegratedImuMeasurements& preintegratedMeasurements);
313 
314  virtual ~ImuFactor2() {
315  }
316 
318  virtual gtsam::NonlinearFactor::shared_ptr clone() const;
319 
322  GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os, const ImuFactor2&);
323  virtual void print(const std::string& s, const KeyFormatter& keyFormatter =
324  DefaultKeyFormatter) const;
325  virtual bool equals(const NonlinearFactor& expected, double tol = 1e-9) const;
327 
331  return _PIM_;
332  }
333 
336  Vector evaluateError(const NavState& state_i, const NavState& state_j,
338  const imuBias::ConstantBias& bias_i, //
339  boost::optional<Matrix&> H1 = boost::none,
340  boost::optional<Matrix&> H2 = boost::none,
341  boost::optional<Matrix&> H3 = boost::none) const;
342 
343 private:
344 
346  friend class boost::serialization::access;
347  template<class ARCHIVE>
348  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
349  ar & boost::serialization::make_nvp("NoiseModelFactor3",
350  boost::serialization::base_object<Base>(*this));
351  ar & BOOST_SERIALIZATION_NVP(_PIM_);
352  }
353 };
354 // class ImuFactor2
355 
356 template <>
357 struct traits<PreintegratedImuMeasurements> : public Testable<PreintegratedImuMeasurements> {};
358 
359 template <>
360 struct traits<ImuFactor> : public Testable<ImuFactor> {};
361 
362 template <>
363 struct traits<ImuFactor2> : public Testable<ImuFactor2> {};
364 
365 }
const PreintegratedImuMeasurements & preintegratedMeasurements() const
Access the preintegrated measurements.
Definition: ImuFactor.h:330
This is the base class for all factor types.
Definition: Factor.h:54
Definition: ImuFactor.h:292
Navigation state: Pose (rotation, translation) + velocity NOTE(frank): it does not make sense to make...
Definition: NavState.h:34
boost::shared_ptr< ImuFactor > shared_ptr
Shorthand for a smart pointer to a factor.
Definition: ImuFactor.h:199
void print(const Matrix &A, const string &s, ostream &stream)
print without optional string, must specify cout yourself
Definition: Matrix.cpp:141
Matrix preintMeasCov() const
Return pre-integrated measurement covariance.
Definition: ImuFactor.h:136
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:57
IMU pre-integration on NavSatet manifold.
Definition: ManifoldPreintegration.h:33
Template to create a binary predicate.
Definition: Testable.h:110
A helper that implements the traits interface for GTSAM types.
Definition: Testable.h:150
Definition: ImuFactor.h:183
boost::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:33
Definition: ImuBias.h:30
const PreintegratedImuMeasurements & preintegratedMeasurements() const
Access the preintegrated measurements.
Definition: ImuFactor.h:232
PreintegratedImuMeasurements(const PreintegrationType &base, const Matrix9 &preintMeasCov)
Construct preintegrated directly from members: base class and preintMeasCov.
Definition: ImuFactor.h:104
PreintegratedImuMeasurements(const boost::shared_ptr< PreintegrationParams > &p, const imuBias::ConstantBias &biasHat=imuBias::ConstantBias())
Constructor, initializes the class with no measurements.
Definition: ImuFactor.h:93
PreintegratedImuMeasurements()
Default constructor for serialization and Cython wrapper.
Definition: ImuFactor.h:84
A convenient base class for creating your own NoiseModelFactor with 3 variables.
Definition: NonlinearFactor.h:420
Matrix9 preintMeasCov_
COVARIANCE OF: [PreintROTATION PreintPOSITION PreintVELOCITY].
Definition: ImuFactor.h:78
ImuFactor()
Default constructor - only use for serialization.
Definition: ImuFactor.h:203
Definition: ImuFactor.h:71
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
Non-linear factor base classes.
Global debugging flags.
A convenient base class for creating your own NoiseModelFactor with 5 variables.
Definition: NonlinearFactor.h:578
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
Definition: Pose3.h:37
virtual ~PreintegratedImuMeasurements()
Virtual destructor.
Definition: ImuFactor.h:110
ImuFactor2()
Default constructor - only use for serialization.
Definition: ImuFactor.h:303