#include <PreintegrationParams.h>
Public Member Functions | |
bool | equals (const PreintegratedRotationParams &other, double tol) const override |
const Matrix3 & | getAccelerometerCovariance () const |
const Vector3 & | getGravity () 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< Pose3 > | getBodyPSensor () const |
const Matrix3 & | getGyroscopeCovariance () const |
std::optional< Vector3 > | getOmegaCoriolis () 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< PreintegrationParams > | MakeSharedD (double g=9.81) |
static std::shared_ptr< PreintegrationParams > | MakeSharedU (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< Pose3 > | body_P_sensor |
The pose of the sensor in the body frame. More... | |
Matrix3 | gyroscopeCovariance |
std::optional< Vector3 > | omegaCoriolis |
Coriolis constant. More... | |
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.
|
inline |
Default constructor for serialization only.
Definition at line 34 of file PreintegrationParams.h.
|
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.
|
overridevirtual |
Reimplemented from gtsam::PreintegratedRotationParams.
Definition at line 41 of file PreintegrationParams.cpp.
|
inline |
Definition at line 67 of file PreintegrationParams.h.
|
inline |
Definition at line 69 of file PreintegrationParams.h.
|
inline |
Definition at line 68 of file PreintegrationParams.h.
|
inline |
Definition at line 70 of file PreintegrationParams.h.
|
inlinestatic |
Definition at line 51 of file PreintegrationParams.h.
|
inlinestatic |
Definition at line 56 of file PreintegrationParams.h.
|
overridevirtual |
Reimplemented from gtsam::PreintegratedRotationParams.
Definition at line 29 of file PreintegrationParams.cpp.
|
inline |
Definition at line 63 of file PreintegrationParams.h.
|
inline |
Definition at line 64 of file PreintegrationParams.h.
|
inline |
Definition at line 65 of file PreintegrationParams.h.
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.
Matrix3 gtsam::PreintegrationParams::integrationCovariance |
continuous-time "Covariance" describing integration uncertainty
Definition at line 29 of file PreintegrationParams.h.
Vector3 gtsam::PreintegrationParams::n_gravity |
Gravity vector in nav frame.
Definition at line 31 of file PreintegrationParams.h.
bool gtsam::PreintegrationParams::use2ndOrderCoriolis |
Whether to use second order Coriolis integration.
Definition at line 30 of file PreintegrationParams.h.