Public Member Functions | Static Public Member Functions | Public Attributes | List of all members
gtsam::PreintegrationParams Struct Reference

#include <PreintegrationParams.h>

Inheritance diagram for gtsam::PreintegrationParams:
Inheritance graph
[legend]

Public Member Functions

bool equals (const PreintegratedRotationParams &other, double tol) const override
 
const Matrix3 & getAccelerometerCovariance () const
 
const Vector3getGravity () const
 
const Matrix3 & getIntegrationCovariance () const
 
bool getUse2ndOrderCoriolis () const
 
 PreintegrationParams ()
 Default constructor for serialization only. More...
 
 PreintegrationParams (const Vector3 &n_gravity_)
 
void print (const std::string &s="") const override
 
void setAccelerometerCovariance (const Matrix3 &cov)
 
void setIntegrationCovariance (const Matrix3 &cov)
 
void setUse2ndOrderCoriolis (bool flag)
 
- Public Member Functions inherited from gtsam::PreintegratedRotationParams
std::optional< Pose3getBodyPSensor () const
 
const Matrix3 & getGyroscopeCovariance () const
 
std::optional< Vector3getOmegaCoriolis () const
 
 PreintegratedRotationParams ()
 
 PreintegratedRotationParams (const Matrix3 &gyroscope_covariance, std::optional< Vector3 > omega_coriolis)
 
void setBodyPSensor (const Pose3 &pose)
 
void setGyroscopeCovariance (const Matrix3 &cov)
 
void setOmegaCoriolis (const Vector3 &omega)
 
virtual ~PreintegratedRotationParams ()
 

Static Public Member Functions

static std::shared_ptr< PreintegrationParamsMakeSharedD (double g=9.81)
 
static std::shared_ptr< PreintegrationParamsMakeSharedU (double g=9.81)
 

Public Attributes

Matrix3 accelerometerCovariance
 
Matrix3 integrationCovariance
 continuous-time "Covariance" describing integration uncertainty More...
 
Vector3 n_gravity
 Gravity vector in nav frame. More...
 
bool use2ndOrderCoriolis
 Whether to use second order Coriolis integration. More...
 
- Public Attributes inherited from gtsam::PreintegratedRotationParams
std::optional< Pose3body_P_sensor
 The pose of the sensor in the body frame. More...
 
Matrix3 gyroscopeCovariance
 
std::optional< Vector3omegaCoriolis
 Coriolis constant. More...
 

Detailed Description

Parameters for pre-integration: Usage: Create just a single Params and pass a shared pointer to the constructor

Definition at line 25 of file PreintegrationParams.h.

Constructor & Destructor Documentation

◆ PreintegrationParams() [1/2]

gtsam::PreintegrationParams::PreintegrationParams ( )
inline

Default constructor for serialization only.

Definition at line 34 of file PreintegrationParams.h.

◆ PreintegrationParams() [2/2]

gtsam::PreintegrationParams::PreintegrationParams ( const Vector3 n_gravity_)
inline

The Params constructor insists on getting the navigation frame gravity vector For convenience, two commonly used conventions are provided by named constructors below

Definition at line 43 of file PreintegrationParams.h.

Member Function Documentation

◆ equals()

bool gtsam::PreintegrationParams::equals ( const PreintegratedRotationParams other,
double  tol 
) const
overridevirtual

Reimplemented from gtsam::PreintegratedRotationParams.

Definition at line 41 of file PreintegrationParams.cpp.

◆ getAccelerometerCovariance()

const Matrix3& gtsam::PreintegrationParams::getAccelerometerCovariance ( ) const
inline

Definition at line 67 of file PreintegrationParams.h.

◆ getGravity()

const Vector3& gtsam::PreintegrationParams::getGravity ( ) const
inline

Definition at line 69 of file PreintegrationParams.h.

◆ getIntegrationCovariance()

const Matrix3& gtsam::PreintegrationParams::getIntegrationCovariance ( ) const
inline

Definition at line 68 of file PreintegrationParams.h.

◆ getUse2ndOrderCoriolis()

bool gtsam::PreintegrationParams::getUse2ndOrderCoriolis ( ) const
inline

Definition at line 70 of file PreintegrationParams.h.

◆ MakeSharedD()

static std::shared_ptr<PreintegrationParams> gtsam::PreintegrationParams::MakeSharedD ( double  g = 9.81)
inlinestatic

Definition at line 51 of file PreintegrationParams.h.

◆ MakeSharedU()

static std::shared_ptr<PreintegrationParams> gtsam::PreintegrationParams::MakeSharedU ( double  g = 9.81)
inlinestatic

Definition at line 56 of file PreintegrationParams.h.

◆ print()

void gtsam::PreintegrationParams::print ( const std::string &  s = "") const
overridevirtual

Reimplemented from gtsam::PreintegratedRotationParams.

Definition at line 29 of file PreintegrationParams.cpp.

◆ setAccelerometerCovariance()

void gtsam::PreintegrationParams::setAccelerometerCovariance ( const Matrix3 &  cov)
inline

Definition at line 63 of file PreintegrationParams.h.

◆ setIntegrationCovariance()

void gtsam::PreintegrationParams::setIntegrationCovariance ( const Matrix3 &  cov)
inline

Definition at line 64 of file PreintegrationParams.h.

◆ setUse2ndOrderCoriolis()

void gtsam::PreintegrationParams::setUse2ndOrderCoriolis ( bool  flag)
inline

Definition at line 65 of file PreintegrationParams.h.

Member Data Documentation

◆ accelerometerCovariance

Matrix3 gtsam::PreintegrationParams::accelerometerCovariance

Continuous-time "Covariance" of accelerometer The units for stddev are σ = m/s²/√Hz

Definition at line 28 of file PreintegrationParams.h.

◆ integrationCovariance

Matrix3 gtsam::PreintegrationParams::integrationCovariance

continuous-time "Covariance" describing integration uncertainty

Definition at line 29 of file PreintegrationParams.h.

◆ n_gravity

Vector3 gtsam::PreintegrationParams::n_gravity

Gravity vector in nav frame.

Definition at line 31 of file PreintegrationParams.h.

◆ use2ndOrderCoriolis

bool gtsam::PreintegrationParams::use2ndOrderCoriolis

Whether to use second order Coriolis integration.

Definition at line 30 of file PreintegrationParams.h.


The documentation for this struct was generated from the following files:


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:24:41