gtsam  4.0.0
gtsam
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 
22 #pragma once
23 
24 /* GTSAM includes */
28 #include <gtsam/base/Matrix.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  * REFERENCES:
45  * [1] G.S. Chirikjian, "Stochastic Models, Information Theory, and Lie Groups",
46  * Volume 2, 2008.
47  * [2] T. Lupton and S.Sukkarieh, "Visual-Inertial-Aided Navigation for
48  * High-Dynamic Motion in Built Environments Without Initial Conditions",
49  * TRO, 28(1):61-76, 2012.
50  * [3] L. Carlone, S. Williams, R. Roberts, "Preintegrated IMU factor:
51  * Computation of the Jacobian Matrices", Tech. Report, 2013.
52  * [4] C. Forster, L. Carlone, F. Dellaert, D. Scaramuzza, IMU Preintegration on
53  * Manifold for Efficient Visual-Inertial Maximum-a-Posteriori Estimation,
54  * Robotics: Science and Systems (RSS), 2015.
55  */
56 
68 
69 public:
70 
76  Matrix6 biasAccOmegaInt;
77 
79  Params(const Vector3& n_gravity) :
81  I_3x3), biasAccOmegaInt(I_6x6) {
82  }
83 
84  // Default Params for a Z-down navigation frame, such as NED: gravity points along positive Z-axis
85  static boost::shared_ptr<Params> MakeSharedD(double g = 9.81) {
86  return boost::shared_ptr<Params>(new Params(Vector3(0, 0, g)));
87  }
88 
89  // Default Params for a Z-up navigation frame, such as ENU: gravity points along negative Z-axis
90  static boost::shared_ptr<Params> MakeSharedU(double g = 9.81) {
91  return boost::shared_ptr<Params>(new Params(Vector3(0, 0, -g)));
92  }
93 
94  private:
96  Params() {}
97 
100  template <class ARCHIVE>
101  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
102  ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegratedRotation::Params);
103  ar& BOOST_SERIALIZATION_NVP(biasAccCovariance);
104  ar& BOOST_SERIALIZATION_NVP(biasOmegaCovariance);
105  ar& BOOST_SERIALIZATION_NVP(biasAccOmegaInt);
106  }
107 
108  public:
109  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
110  };
111 
112  protected:
113  /* Covariance matrix of the preintegrated measurements
114  * COVARIANCE OF: [PreintROTATION PreintPOSITION PreintVELOCITY BiasAcc BiasOmega]
115  * (first-order propagation from *measurementCovariance*).
116  * PreintegratedCombinedMeasurements also include the biases and keep the correlation
117  * between the preintegrated measurements and the biases
118  */
119  Eigen::Matrix<double, 15, 15> preintMeasCov_;
120 
121 
122  friend class CombinedImuFactor;
123 
124  public:
127 
130 
136  const boost::shared_ptr<Params>& p,
137  const imuBias::ConstantBias& biasHat = imuBias::ConstantBias())
138  : PreintegrationType(p, biasHat) {
139  preintMeasCov_.setZero();
140  }
141 
143 
146 
148  void resetIntegration() override;
149 
151  Params& p() const { return *boost::static_pointer_cast<Params>(this->p_);}
153 
156  Matrix preintMeasCov() const { return preintMeasCov_; }
158 
161  void print(const std::string& s = "Preintegrated Measurements:") const override;
162  bool equals(const PreintegratedCombinedMeasurements& expected, double tol = 1e-9) const;
164 
167 
177  void integrateMeasurement(const Vector3& measuredAcc,
178  const Vector3& measuredOmega, const double dt) override;
179 
181 
182 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4
183  PreintegratedCombinedMeasurements(const imuBias::ConstantBias& biasHat,
186  const Matrix3& measuredAccCovariance,
187  const Matrix3& measuredOmegaCovariance,
188  const Matrix3& integrationErrorCovariance,
189  const Matrix3& biasAccCovariance, const Matrix3& biasOmegaCovariance,
190  const Matrix6& biasAccOmegaInt, const bool use2ndOrderIntegration = true);
191 #endif
192 
193  private:
196  template <class ARCHIVE>
197  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
198  ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationType);
199  ar& BOOST_SERIALIZATION_NVP(preintMeasCov_);
200  }
201 
202 public:
203  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
204 };
205 
225 class CombinedImuFactor: public NoiseModelFactor6<Pose3, Vector3, Pose3,
226  Vector3, imuBias::ConstantBias, imuBias::ConstantBias> {
227 public:
228 
229 private:
230 
231  typedef CombinedImuFactor This;
232  typedef NoiseModelFactor6<Pose3, Vector3, Pose3, Vector3,
234 
236 
238  CombinedImuFactor() {}
239 
240 public:
241 
243 #if !defined(_MSC_VER) && __GNUC__ == 4 && __GNUC_MINOR__ > 5
244  typedef typename boost::shared_ptr<CombinedImuFactor> shared_ptr;
245 #else
246  typedef boost::shared_ptr<CombinedImuFactor> shared_ptr;
247 #endif
248 
260  Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias_i, Key bias_j,
262 
263  virtual ~CombinedImuFactor() {}
264 
266  virtual gtsam::NonlinearFactor::shared_ptr clone() const;
267 
270  virtual void print(const std::string& s, const KeyFormatter& keyFormatter =
272  DefaultKeyFormatter) const;
273 
275  virtual bool equals(const NonlinearFactor& expected, double tol = 1e-9) const;
276 
280  return _PIM_;
281  }
282 
285  Vector evaluateError(const Pose3& pose_i, const Vector3& vel_i,
287  const Pose3& pose_j, const Vector3& vel_j,
288  const imuBias::ConstantBias& bias_i, const imuBias::ConstantBias& bias_j,
289  boost::optional<Matrix&> H1 = boost::none, boost::optional<Matrix&> H2 =
290  boost::none, boost::optional<Matrix&> H3 = boost::none,
291  boost::optional<Matrix&> H4 = boost::none, boost::optional<Matrix&> H5 =
292  boost::none, boost::optional<Matrix&> H6 = boost::none) const;
293 
294 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4
295  typedef gtsam::PreintegratedCombinedMeasurements CombinedPreintegratedMeasurements;
297 
299  CombinedImuFactor(Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias_i,
300  Key bias_j, const CombinedPreintegratedMeasurements& pim,
301  const Vector3& n_gravity, const Vector3& omegaCoriolis,
302  const boost::optional<Pose3>& body_P_sensor = boost::none,
303  const bool use2ndOrderCoriolis = false);
304 
305  // @deprecated use PreintegrationBase::predict
306  static void Predict(const Pose3& pose_i, const Vector3& vel_i, Pose3& pose_j,
307  Vector3& vel_j, const imuBias::ConstantBias& bias_i,
308  CombinedPreintegratedMeasurements& pim,
309  const Vector3& n_gravity, const Vector3& omegaCoriolis,
310  const bool use2ndOrderCoriolis = false);
311 #endif
312 
313 private:
314 
317  template<class ARCHIVE>
318  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
319  ar & boost::serialization::make_nvp("NoiseModelFactor6",
320  boost::serialization::base_object<Base>(*this));
321  ar & BOOST_SERIALIZATION_NVP(_PIM_);
322  }
323 
324 public:
325  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
326 };
327 // class CombinedImuFactor
328 
329 }
Vector3 n_gravity
Gravity vector in nav frame.
Definition: PreintegrationParams.h:30
virtual bool equals(const NonlinearFactor &expected, double tol=1e-9) const
equals
Definition: CombinedImuFactor.cpp:175
This is the base class for all factor types.
Definition: Factor.h:54
Params(const Vector3 &n_gravity)
See two named constructors below for good values of n_gravity in body frame.
Definition: CombinedImuFactor.h:79
virtual gtsam::NonlinearFactor::shared_ptr clone() const
Definition: CombinedImuFactor.cpp:158
Parameters for pre-integration: Usage: Create just a single Params and pass a shared pointer to the c...
Definition: CombinedImuFactor.h:73
void print(const Matrix &A, const string &s, ostream &stream)
print without optional string, must specify cout yourself
Definition: Matrix.cpp:141
Parameters for pre-integration: Usage: Create just a single Params and pass a shared pointer to the c...
Definition: PreintegratedRotation.h:31
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:57
void integrateMeasurement(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt) override
Add a single IMU measurement to the preintegration.
Definition: CombinedImuFactor.cpp:67
IMU pre-integration on NavSatet manifold.
Definition: ManifoldPreintegration.h:33
boost::shared_ptr< Params > p_
Parameters.
Definition: PreintegrationBase.h:71
Definition: CombinedImuFactor.h:67
Matrix6 biasAccOmegaInt
covariance of bias used for pre-integration
Definition: CombinedImuFactor.h:76
PreintegratedCombinedMeasurements()
Default constructor only for serialization and Cython wrapper.
Definition: CombinedImuFactor.h:129
Params & p() const
const reference to params, shadows definition in base class
Definition: CombinedImuFactor.h:151
friend class boost::serialization::access
Serialization function.
Definition: CombinedImuFactor.h:316
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
Nonlinear factor base class.
Definition: NonlinearFactor.h:50
Definition: CombinedImuFactor.h:225
A convenient base class for creating your own NoiseModelFactor with 6 variables.
Definition: NonlinearFactor.h:663
Non-linear factor base classes.
virtual void print(const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
implement functions needed for Testable
Definition: CombinedImuFactor.cpp:164
friend class boost::serialization::access
Serialization function.
Definition: CombinedImuFactor.h:195
Vector evaluateError(const Pose3 &pose_i, const Vector3 &vel_i, const Pose3 &pose_j, const Vector3 &vel_j, const imuBias::ConstantBias &bias_i, const imuBias::ConstantBias &bias_j, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none, boost::optional< Matrix & > H4=boost::none, boost::optional< Matrix & > H5=boost::none, boost::optional< Matrix & > H6=boost::none) const
implement functions needed to derive from Factor
Definition: CombinedImuFactor.cpp:181
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
void resetIntegration() override
Re-initialize PreintegratedCombinedMeasurements.
Definition: CombinedImuFactor.cpp:47
const PreintegratedCombinedMeasurements & preintegratedMeasurements() const
Access the preintegrated measurements.
Definition: CombinedImuFactor.h:279
typedef and functions to augment Eigen's MatrixXd
Matrix3 biasOmegaCovariance
continuous-time "Covariance" describing gyroscope bias random walk
Definition: CombinedImuFactor.h:75
boost::shared_ptr< CombinedImuFactor > shared_ptr
Shorthand for a smart pointer to a factor.
Definition: CombinedImuFactor.h:246
Definition: Pose3.h:37
PreintegratedCombinedMeasurements(const boost::shared_ptr< Params > &p, const imuBias::ConstantBias &biasHat=imuBias::ConstantBias())
Default constructor, initializes the class with no measurements.
Definition: CombinedImuFactor.h:135
Parameters for pre-integration: Usage: Create just a single Params and pass a shared pointer to the c...
Definition: PreintegrationParams.h:26
Matrix3 biasAccCovariance
continuous-time "Covariance" describing accelerometer bias random walk
Definition: CombinedImuFactor.h:74
friend class boost::serialization::access
Serialization function.
Definition: CombinedImuFactor.h:99