GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
CombinedImuFactor.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 
23 #pragma once
24 
25 /* GTSAM includes */
29 #include <gtsam/base/Matrix.h>
30 
31 namespace gtsam {
32 
33 #ifdef GTSAM_TANGENT_PREINTEGRATION
34 typedef TangentPreintegration PreintegrationType;
35 #else
36 typedef ManifoldPreintegration PreintegrationType;
37 #endif
38 
39 /*
40  * If you are using the factor, please cite:
41  * L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert, Eliminating
42  * conditionally independent sets in factor graphs: a unifying perspective based
43  * on smart factors, Int. Conf. on Robotics and Automation (ICRA), 2014.
44  *
45  * REFERENCES:
46  * [1] G.S. Chirikjian, "Stochastic Models, Information Theory, and Lie Groups",
47  * Volume 2, 2008.
48  * [2] T. Lupton and S.Sukkarieh, "Visual-Inertial-Aided Navigation for
49  * High-Dynamic Motion in Built Environments Without Initial Conditions",
50  * TRO, 28(1):61-76, 2012.
51  * [3] L. Carlone, S. Williams, R. Roberts, "Preintegrated IMU factor:
52  * Computation of the Jacobian Matrices", Tech. Report, 2013.
53  * Available in this repo as "PreintegratedIMUJacobians.pdf".
54  * [4] C. Forster, L. Carlone, F. Dellaert, D. Scaramuzza, IMU Preintegration on
55  * Manifold for Efficient Visual-Inertial Maximum-a-Posteriori Estimation,
56  * Robotics: Science and Systems (RSS), 2015.
57  */
58 
64  Matrix6 biasAccOmegaInt;
65 
69  : biasAccCovariance(I_3x3),
70  biasOmegaCovariance(I_3x3),
71  biasAccOmegaInt(I_6x6) {}
72 
74  PreintegrationCombinedParams(const Vector3& _n_gravity) :
75  PreintegrationParams(_n_gravity), biasAccCovariance(I_3x3),
76  biasOmegaCovariance(I_3x3), biasAccOmegaInt(I_6x6) {
77 
78  }
79 
80  // Default Params for a Z-down navigation frame, such as NED: gravity points along positive Z-axis
81  static std::shared_ptr<PreintegrationCombinedParams> MakeSharedD(double g = 9.81) {
82  return std::shared_ptr<PreintegrationCombinedParams>(new PreintegrationCombinedParams(Vector3(0, 0, g)));
83  }
84 
85  // Default Params for a Z-up navigation frame, such as ENU: gravity points along negative Z-axis
86  static std::shared_ptr<PreintegrationCombinedParams> MakeSharedU(double g = 9.81) {
87  return std::shared_ptr<PreintegrationCombinedParams>(new PreintegrationCombinedParams(Vector3(0, 0, -g)));
88  }
89 
90  void print(const std::string& s="") const override;
91  bool equals(const PreintegratedRotationParams& other, double tol) const override;
92 
93  void setBiasAccCovariance(const Matrix3& cov) { biasAccCovariance=cov; }
94  void setBiasOmegaCovariance(const Matrix3& cov) { biasOmegaCovariance=cov; }
95  void setBiasAccOmegaInit(const Matrix6& cov) { biasAccOmegaInt=cov; }
96 
97  const Matrix3& getBiasAccCovariance() const { return biasAccCovariance; }
98  const Matrix3& getBiasOmegaCovariance() const { return biasOmegaCovariance; }
99  const Matrix6& getBiasAccOmegaInit() const { return biasAccOmegaInt; }
100 
101 private:
102 
103 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
104 
105  friend class boost::serialization::access;
106  template <class ARCHIVE>
107  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
108  namespace bs = ::boost::serialization;
109  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationParams);
110  ar & BOOST_SERIALIZATION_NVP(biasAccCovariance);
111  ar & BOOST_SERIALIZATION_NVP(biasOmegaCovariance);
112  ar & BOOST_SERIALIZATION_NVP(biasAccOmegaInt);
113  }
114 #endif
115 
116 public:
118 };
119 
130 class GTSAM_EXPORT PreintegratedCombinedMeasurements : public PreintegrationType {
131 
132 public:
134 
135  protected:
136  /* Covariance matrix of the preintegrated measurements
137  * COVARIANCE OF: [PreintROTATION PreintPOSITION PreintVELOCITY BiasAcc BiasOmega]
138  * (first-order propagation from *measurementCovariance*).
139  * PreintegratedCombinedMeasurements also include the biases and keep the correlation
140  * between the preintegrated measurements and the biases
141  */
142  Eigen::Matrix<double, 15, 15> preintMeasCov_;
143 
144  friend class CombinedImuFactor;
145 
146  public:
149 
152  preintMeasCov_.setZero();
153  }
154 
161  const std::shared_ptr<Params>& p,
162  const imuBias::ConstantBias& biasHat = imuBias::ConstantBias())
163  : PreintegrationType(p, biasHat) {
164  preintMeasCov_.setZero();
165  }
166 
172  PreintegratedCombinedMeasurements(const PreintegrationType& base, const Eigen::Matrix<double, 15, 15>& preintMeasCov)
173  : PreintegrationType(base),
174  preintMeasCov_(preintMeasCov) {
175  }
176 
179 
181 
184 
186  void resetIntegration() override;
187 
189  Params& p() const { return *std::static_pointer_cast<Params>(this->p_); }
191 
195  Matrix preintMeasCov() const { return preintMeasCov_; }
197 
201  void print(const std::string& s = "Preintegrated Measurements:") const override;
203  bool equals(const PreintegratedCombinedMeasurements& expected,
204  double tol = 1e-9) const;
206 
207 
210 
221  void integrateMeasurement(const Vector3& measuredAcc,
222  const Vector3& measuredOmega, const double dt) override;
223 
225 
226  private:
227 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
228  friend class boost::serialization::access;
230  template <class ARCHIVE>
231  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
232  namespace bs = ::boost::serialization;
233  ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationType);
234  ar& BOOST_SERIALIZATION_NVP(preintMeasCov_);
235  }
236 #endif
237 
238 public:
240 };
241 
261 class GTSAM_EXPORT CombinedImuFactor: public NoiseModelFactorN<Pose3, Vector3, Pose3,
262  Vector3, imuBias::ConstantBias, imuBias::ConstantBias> {
263 public:
264 
265 private:
266 
267  typedef CombinedImuFactor This;
268  typedef NoiseModelFactorN<Pose3, Vector3, Pose3, Vector3,
269  imuBias::ConstantBias, imuBias::ConstantBias> Base;
270 
272 
273 public:
274 
275  // Provide access to Matrix& version of evaluateError:
276  using Base::evaluateError;
277 
279 #if !defined(_MSC_VER) && __GNUC__ == 4 && __GNUC_MINOR__ > 5
280  typedef typename std::shared_ptr<CombinedImuFactor> shared_ptr;
281 #else
282  typedef std::shared_ptr<CombinedImuFactor> shared_ptr;
283 #endif
284 
287 
299  Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias_i, Key bias_j,
300  const PreintegratedCombinedMeasurements& preintegratedMeasurements);
301 
302  ~CombinedImuFactor() override {}
303 
305  gtsam::NonlinearFactor::shared_ptr clone() const override;
306 
309  GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os,
312  const CombinedImuFactor&);
314  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
315  DefaultKeyFormatter) const override;
316 
318  bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;
320 
324  return _PIM_;
325  }
326 
329  Vector evaluateError(const Pose3& pose_i, const Vector3& vel_i,
331  const Pose3& pose_j, const Vector3& vel_j,
332  const imuBias::ConstantBias& bias_i, const imuBias::ConstantBias& bias_j,
335  OptionalMatrixType H5, OptionalMatrixType H6) const override;
336 
337  private:
338 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
339 
340  friend class boost::serialization::access;
341  template <class ARCHIVE>
342  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
343  // NoiseModelFactor6 instead of NoiseModelFactorN for backward compatibility
344  ar& boost::serialization::make_nvp(
345  "NoiseModelFactor6", boost::serialization::base_object<Base>(*this));
346  ar& BOOST_SERIALIZATION_NVP(_PIM_);
347  }
348 #endif
349 
350 public:
352 };
353 // class CombinedImuFactor
354 
355 template <>
357  : public Testable<PreintegrationCombinedParams> {};
358 
359 template <>
361  : public Testable<PreintegratedCombinedMeasurements> {};
362 
363 template <>
364 struct traits<CombinedImuFactor> : public Testable<CombinedImuFactor> {};
365 
366 } // namespace gtsam
Definition: NonlinearFactor.h:431
std::shared_ptr< CombinedImuFactor > shared_ptr
Definition: CombinedImuFactor.h:282
Definition: ImuBias.h:32
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:113
Matrix6 biasAccOmegaInt
covariance of bias used as initial estimate.
Definition: CombinedImuFactor.h:64
Definition: Factor.h:69
Definition: Testable.h:152
Definition: Group.h:43
Definition: CombinedImuFactor.h:130
Params & p() const
const reference to params, shadows definition in base class
Definition: CombinedImuFactor.h:189
Definition: NonlinearFactor.h:68
PreintegratedCombinedMeasurements()
Default constructor only for serialization and wrappers.
Definition: CombinedImuFactor.h:151
const PreintegratedCombinedMeasurements & preintegratedMeasurements() const
Definition: CombinedImuFactor.h:323
CombinedImuFactor()
Definition: CombinedImuFactor.h:286
Definition: Testable.h:112
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:55
PreintegrationCombinedParams(const Vector3 &_n_gravity)
See two named constructors below for good values of n_gravity in body frame.
Definition: CombinedImuFactor.h:74
~PreintegratedCombinedMeasurements() override
Virtual destructor.
Definition: CombinedImuFactor.h:178
GTSAM_EXPORT void print(const Matrix &A, const std::string &s, std::ostream &stream)
PreintegrationCombinedParams()
Definition: CombinedImuFactor.h:68
typedef and functions to augment Eigen&#39;s MatrixXd
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
Definition: CombinedImuFactor.h:61
Definition: chartTesting.h:28
Matrix3 biasOmegaCovariance
continuous-time "Covariance" describing gyroscope bias random walk
Definition: CombinedImuFactor.h:63
PreintegratedCombinedMeasurements(const std::shared_ptr< Params > &p, const imuBias::ConstantBias &biasHat=imuBias::ConstantBias())
Definition: CombinedImuFactor.h:160
Non-linear factor base classes.
Definition: PreintegratedRotation.h:32
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:284
PreintegratedCombinedMeasurements(const PreintegrationType &base, const Eigen::Matrix< double, 15, 15 > &preintMeasCov)
Definition: CombinedImuFactor.h:172
Definition: CombinedImuFactor.h:261
Definition: Pose3.h:37
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
Definition: PreintegrationParams.h:25
Matrix3 biasAccCovariance
continuous-time "Covariance" describing accelerometer bias random walk
Definition: CombinedImuFactor.h:62