PreintegrationParams.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 
17 #pragma once
18 
20 
21 namespace gtsam {
22 
32 
36  accelerometerCovariance(I_3x3),
37  integrationCovariance(I_3x3),
38  use2ndOrderCoriolis(false),
39  n_gravity(0, 0, -1) {}
40 
43  PreintegrationParams(const Vector3& n_gravity_)
45  accelerometerCovariance(I_3x3),
46  integrationCovariance(I_3x3),
47  use2ndOrderCoriolis(false),
48  n_gravity(n_gravity_) {}
49 
50  // Default Params for a Z-down navigation frame, such as NED: gravity points along positive Z-axis
51  static std::shared_ptr<PreintegrationParams> MakeSharedD(double g = 9.81) {
52  return std::shared_ptr<PreintegrationParams>(new PreintegrationParams(Vector3(0, 0, g)));
53  }
54 
55  // Default Params for a Z-up navigation frame, such as ENU: gravity points along negative Z-axis
56  static std::shared_ptr<PreintegrationParams> MakeSharedU(double g = 9.81) {
57  return std::shared_ptr<PreintegrationParams>(new PreintegrationParams(Vector3(0, 0, -g)));
58  }
59 
60  void print(const std::string& s="") const override;
61  bool equals(const PreintegratedRotationParams& other, double tol) const override;
62 
63  void setAccelerometerCovariance(const Matrix3& cov) { accelerometerCovariance = cov; }
64  void setIntegrationCovariance(const Matrix3& cov) { integrationCovariance = cov; }
65  void setUse2ndOrderCoriolis(bool flag) { use2ndOrderCoriolis = flag; }
66 
67  const Matrix3& getAccelerometerCovariance() const { return accelerometerCovariance; }
68  const Matrix3& getIntegrationCovariance() const { return integrationCovariance; }
69  const Vector3& getGravity() const { return n_gravity; }
70  bool getUse2ndOrderCoriolis() const { return use2ndOrderCoriolis; }
71 
72 protected:
73 
74 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
75 
76  friend class boost::serialization::access;
77  template<class ARCHIVE>
78  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
79  namespace bs = ::boost::serialization;
80  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegratedRotationParams);
81  ar & BOOST_SERIALIZATION_NVP(accelerometerCovariance);
82  ar & BOOST_SERIALIZATION_NVP(integrationCovariance);
83  ar & BOOST_SERIALIZATION_NVP(use2ndOrderCoriolis);
84  ar & BOOST_SERIALIZATION_NVP(n_gravity);
85  }
86 #endif
87 
88 #ifdef GTSAM_USE_QUATERNIONS
89  // Align if we are using Quaternions
90 public:
92 #endif
93 };
94 
95 } // namespace gtsam
gtsam::PreintegrationParams::n_gravity
Vector3 n_gravity
Gravity vector in nav frame.
Definition: PreintegrationParams.h:31
gtsam::PreintegratedRotationParams
Definition: PreintegratedRotation.h:57
gtsam::PreintegrationParams::setIntegrationCovariance
void setIntegrationCovariance(const Matrix3 &cov)
Definition: PreintegrationParams.h:64
s
RealScalar s
Definition: level1_cplx_impl.h:126
gtsam::PreintegrationParams::accelerometerCovariance
Matrix3 accelerometerCovariance
Definition: PreintegrationParams.h:28
gtsam::PreintegrationParams::getGravity
const Vector3 & getGravity() const
Definition: PreintegrationParams.h:69
gtsam::PreintegrationParams
Definition: PreintegrationParams.h:25
gtsam::PreintegrationParams::PreintegrationParams
PreintegrationParams(const Vector3 &n_gravity_)
Definition: PreintegrationParams.h:43
gtsam::PreintegrationParams::getAccelerometerCovariance
const Matrix3 & getAccelerometerCovariance() const
Definition: PreintegrationParams.h:67
gtsam::PreintegrationParams::getIntegrationCovariance
const Matrix3 & getIntegrationCovariance() const
Definition: PreintegrationParams.h:68
gtsam::PreintegrationParams::integrationCovariance
Matrix3 integrationCovariance
continuous-time "Covariance" describing integration uncertainty
Definition: PreintegrationParams.h:29
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:43
gtsam::PreintegrationParams::setUse2ndOrderCoriolis
void setUse2ndOrderCoriolis(bool flag)
Definition: PreintegrationParams.h:65
gtsam::PreintegrationParams::setAccelerometerCovariance
void setAccelerometerCovariance(const Matrix3 &cov)
Definition: PreintegrationParams.h:63
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
PreintegratedRotation.h
g
void g(const string &key, int i)
Definition: testBTree.cpp:41
gtsam::PreintegrationParams::MakeSharedD
static std::shared_ptr< PreintegrationParams > MakeSharedD(double g=9.81)
Definition: PreintegrationParams.h:51
gtsam::equals
Definition: Testable.h:112
gtsam::PreintegrationParams::use2ndOrderCoriolis
bool use2ndOrderCoriolis
Whether to use second order Coriolis integration.
Definition: PreintegrationParams.h:30
gtsam::PreintegrationParams::MakeSharedU
static std::shared_ptr< PreintegrationParams > MakeSharedU(double g=9.81)
Definition: PreintegrationParams.h:56
gtsam
traits
Definition: SFMdata.h:40
gtsam::PreintegrationParams::getUse2ndOrderCoriolis
bool getUse2ndOrderCoriolis() const
Definition: PreintegrationParams.h:70
gtsam::PreintegrationParams::PreintegrationParams
PreintegrationParams()
Default constructor for serialization only.
Definition: PreintegrationParams.h:34
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam.examples.ImuFactorISAM2Example.n_gravity
def n_gravity
Definition: ImuFactorISAM2Example.py:31
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:279
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:03:37