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 */
27 
28 namespace gtsam {
29 
30 #ifdef GTSAM_TANGENT_PREINTEGRATION
31 typedef TangentPreintegration PreintegrationType;
32 #else
34 #endif
35 
36 /*
37  * If you are using the factor, please cite:
38  * L. Carlone, Z. Kira, C. Beall, V. Indelman, F. Dellaert, Eliminating
39  * conditionally independent sets in factor graphs: a unifying perspective based
40  * on smart factors, Int. Conf. on Robotics and Automation (ICRA), 2014.
41  *
42  * REFERENCES:
43  * [1] G.S. Chirikjian, "Stochastic Models, Information Theory, and Lie Groups",
44  * Volume 2, 2008.
45  * [2] T. Lupton and S.Sukkarieh, "Visual-Inertial-Aided Navigation for
46  * High-Dynamic Motion in Built Environments Without Initial Conditions",
47  * TRO, 28(1):61-76, 2012.
48  * [3] L. Carlone, S. Williams, R. Roberts, "Preintegrated IMU factor:
49  * Computation of the Jacobian Matrices", Tech. Report, 2013.
50  * Available in this repo as "PreintegratedIMUJacobians.pdf".
51  * [4] C. Forster, L. Carlone, F. Dellaert, D. Scaramuzza, IMU Preintegration on
52  * Manifold for Efficient Visual-Inertial Maximum-a-Posteriori Estimation,
53  * Robotics: Science and Systems (RSS), 2015.
54  */
55 
67  : public PreintegrationType {
68  public:
70 
71  protected:
72  /* Covariance matrix of the preintegrated measurements
73  * COVARIANCE OF: [PreintROTATION PreintPOSITION PreintVELOCITY BiasAcc
74  * BiasOmega] (first-order propagation from *measurementCovariance*).
75  * PreintegratedCombinedMeasurements also include the biases and keep the
76  * correlation between the preintegrated measurements and the biases
77  */
79 
80  friend class CombinedImuFactor;
81 
82  public:
85 
87  PreintegratedCombinedMeasurements() { resetIntegration(); }
88 
96  const std::shared_ptr<Params>& p,
98  const Eigen::Matrix<double, 15, 15>& preintMeasCov =
100  : PreintegrationType(p, biasHat), preintMeasCov_(preintMeasCov) {
102  }
103 
111  const PreintegrationType& base,
112  const Eigen::Matrix<double, 15, 15>& preintMeasCov)
113  : PreintegrationType(base), preintMeasCov_(preintMeasCov) {
115  }
116 
119 
121 
124 
126  void resetIntegration() override;
127 
134  void resetIntegration(const gtsam::Matrix6& Q_init);
135 
137  Params& p() const { return *std::static_pointer_cast<Params>(this->p_); }
139 
143  Matrix preintMeasCov() const { return preintMeasCov_; }
145 
149  void print(
150  const std::string& s = "Preintegrated Measurements:") const override;
153  double tol = 1e-9) const;
155 
158 
169  void integrateMeasurement(const Vector3& measuredAcc,
170  const Vector3& measuredOmega,
171  const double dt) override;
172 
174 
175  private:
176 #if GTSAM_ENABLE_BOOST_SERIALIZATION
177  friend class boost::serialization::access;
179  template <class ARCHIVE>
180  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
181  namespace bs = ::boost::serialization;
182  ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationType);
183  ar& BOOST_SERIALIZATION_NVP(preintMeasCov_);
184  }
185 #endif
186 
187  public:
189 };
190 
209 class GTSAM_EXPORT CombinedImuFactor
210  : public NoiseModelFactorN<Pose3, Vector3, Pose3, Vector3,
211  imuBias::ConstantBias, imuBias::ConstantBias> {
212  public:
213  private:
218 
220 
221  public:
222  // Provide access to Matrix& version of evaluateError:
223  using Base::evaluateError;
224 
226 #if !defined(_MSC_VER) && __GNUC__ == 4 && __GNUC_MINOR__ > 5
227  typedef typename std::shared_ptr<CombinedImuFactor> shared_ptr;
228 #else
229  typedef std::shared_ptr<CombinedImuFactor> shared_ptr;
230 #endif
231 
234 
246  Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias_i, Key bias_j,
247  const PreintegratedCombinedMeasurements& preintegratedMeasurements);
248 
249  ~CombinedImuFactor() override {}
250 
252  gtsam::NonlinearFactor::shared_ptr clone() const override;
253 
256  GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os,
259  const CombinedImuFactor&);
261  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
262  DefaultKeyFormatter) const override;
263 
265  bool equals(const NonlinearFactor& expected,
266  double tol = 1e-9) const override;
268 
272  return _PIM_;
273  }
274 
277  Vector evaluateError(const Pose3& pose_i, const Vector3& vel_i,
279  const Pose3& pose_j, const Vector3& vel_j,
280  const imuBias::ConstantBias& bias_i,
281  const imuBias::ConstantBias& bias_j,
285  OptionalMatrixType H6) const override;
286 
287  private:
288 #if GTSAM_ENABLE_BOOST_SERIALIZATION
289 
290  friend class boost::serialization::access;
291  template <class ARCHIVE>
292  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
293  // NoiseModelFactor6 instead of NoiseModelFactorN for backward compatibility
294  ar& boost::serialization::make_nvp(
295  "NoiseModelFactor6", boost::serialization::base_object<Base>(*this));
296  ar& BOOST_SERIALIZATION_NVP(_PIM_);
297  }
298 #endif
299 
300  public:
302 };
303 // class CombinedImuFactor
304 
305 template <>
307  : public Testable<PreintegrationCombinedParams> {};
308 
309 template <>
311  : public Testable<PreintegratedCombinedMeasurements> {};
312 
313 template <>
314 struct traits<CombinedImuFactor> : public Testable<CombinedImuFactor> {};
315 
316 } // namespace gtsam
gtsam::NonlinearFactor::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: NonlinearFactor.h:79
base
Annotation indicating that a class derives from another given type.
Definition: attr.h:64
gtsam::PreintegratedCombinedMeasurements::~PreintegratedCombinedMeasurements
~PreintegratedCombinedMeasurements() override
Virtual destructor.
Definition: CombinedImuFactor.h:118
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::operator<<
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Definition: testGroup.cpp:109
gtsam::CombinedImuFactor::shared_ptr
std::shared_ptr< CombinedImuFactor > shared_ptr
Definition: CombinedImuFactor.h:229
Matrix6
Eigen::Matrix< double, 6, 6 > Matrix6
Definition: IncrementalFixedLagSmootherExample.cpp:77
gtsam::PreintegratedCombinedMeasurements::PreintegratedCombinedMeasurements
PreintegratedCombinedMeasurements(const std::shared_ptr< Params > &p, const imuBias::ConstantBias &biasHat=imuBias::ConstantBias(), const Eigen::Matrix< double, 15, 15 > &preintMeasCov=Eigen::Matrix< double, 15, 15 >::Zero())
Definition: CombinedImuFactor.h:95
dt
const double dt
Definition: testVelocityConstraint.cpp:15
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
gtsam::PreintegratedCombinedMeasurements::Params
PreintegrationCombinedParams Params
Definition: CombinedImuFactor.h:69
os
ofstream os("timeSchurFactors.csv")
gtsam::Factor::shared_ptr
std::shared_ptr< Factor > shared_ptr
A shared_ptr to this class.
Definition: Factor.h:76
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::CombinedImuFactor::This
CombinedImuFactor This
Definition: CombinedImuFactor.h:214
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::CombinedImuFactor::CombinedImuFactor
CombinedImuFactor()
Definition: CombinedImuFactor.h:233
PreintegrationCombinedParams.h
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:145
gtsam::PreintegratedCombinedMeasurements::PreintegratedCombinedMeasurements
PreintegratedCombinedMeasurements(const PreintegrationType &base, const Eigen::Matrix< double, 15, 15 > &preintMeasCov)
Definition: CombinedImuFactor.h:110
biased_x_rotation::measuredOmega
const Vector3 measuredOmega
Definition: testPreintegratedRotation.cpp:35
gtsam::KeyFormatter
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
gtsam::Pose3
Definition: Pose3.h:37
gtsam::NoiseModelFactorN
Definition: NonlinearFactor.h:434
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:916
gtsam::PreintegratedCombinedMeasurements::p
Params & p() const
const reference to params, shadows definition in base class
Definition: CombinedImuFactor.h:137
gtsam::PreintegratedCombinedMeasurements::preintMeasCov_
Eigen::Matrix< double, 15, 15 > preintMeasCov_
Definition: CombinedImuFactor.h:78
gtsam::PreintegrationType
ManifoldPreintegration PreintegrationType
Definition: CombinedImuFactor.h:33
gtsam::equals
Definition: Testable.h:112
gtsam::ManifoldPreintegration
Definition: ManifoldPreintegration.h:33
gtsam::CombinedImuFactor
Definition: CombinedImuFactor.h:209
gtsam::imuBias::ConstantBias
Definition: ImuBias.h:32
gtsam::ManifoldPreintegration::resetIntegration
void resetIntegration() override
Definition: ManifoldPreintegration.cpp:36
gtsam
traits
Definition: SFMdata.h:40
gtsam::CombinedImuFactor::~CombinedImuFactor
~CombinedImuFactor() override
Definition: CombinedImuFactor.h:249
gtsam::Testable
Definition: Testable.h:152
gtsam::traits
Definition: Group.h:36
gtsam::NonlinearFactor
Definition: NonlinearFactor.h:69
gtsam::CombinedImuFactor::Base
NoiseModelFactorN< Pose3, Vector3, Pose3, Vector3, imuBias::ConstantBias, imuBias::ConstantBias > Base
Definition: CombinedImuFactor.h:217
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::PreintegratedCombinedMeasurements::preintMeasCov
Matrix preintMeasCov() const
Definition: CombinedImuFactor.h:143
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::CombinedImuFactor::preintegratedMeasurements
const PreintegratedCombinedMeasurements & preintegratedMeasurements() const
Definition: CombinedImuFactor.h:271
gtsam::OptionalMatrixType
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:56
common::measuredAcc
static const Vector3 measuredAcc
Definition: testImuFactor.cpp:181
Eigen::Matrix< double, 15, 15 >
gtsam::PreintegrationCombinedParams
Definition: PreintegrationCombinedParams.h:36
gtsam::PreintegratedCombinedMeasurements
Definition: CombinedImuFactor.h:66
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::PreintegratedCombinedMeasurements::PreintegratedCombinedMeasurements
PreintegratedCombinedMeasurements()
Default constructor only for serialization and wrappers.
Definition: CombinedImuFactor.h:87
gtsam::CombinedImuFactor::_PIM_
PreintegratedCombinedMeasurements _PIM_
Definition: CombinedImuFactor.h:219
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:279


gtsam
Author(s):
autogenerated on Wed Mar 19 2025 03:01:23