Public Member Functions | Protected Attributes | Friends | List of all members
gtsam::PreintegratedImuMeasurements Class Reference

#include <ImuFactor.h>

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

Public Member Functions

bool equals (const PreintegratedImuMeasurements &expected, double tol=1e-9) const
 equals More...
 
void integrateMeasurement (const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt) override
 
void integrateMeasurements (const Matrix &measuredAccs, const Matrix &measuredOmegas, const Matrix &dts)
 Add multiple measurements, in matrix columns. More...
 
 PreintegratedImuMeasurements ()
 Default constructor for serialization and wrappers. More...
 
 PreintegratedImuMeasurements (const std::shared_ptr< PreintegrationParams > &p, const imuBias::ConstantBias &biasHat=imuBias::ConstantBias())
 
 PreintegratedImuMeasurements (const PreintegrationType &base, const Matrix9 &preintMeasCov)
 
Matrix preintMeasCov () const
 Return pre-integrated measurement covariance. More...
 
void print (const std::string &s="Preintegrated Measurements:") const override
 print More...
 
void resetIntegration () override
 Re-initialize PreintegratedIMUMeasurements. More...
 
 ~PreintegratedImuMeasurements () override
 Virtual destructor. More...
 
- Public Member Functions inherited from gtsam::ManifoldPreintegration
 ManifoldPreintegration (const std::shared_ptr< Params > &p, const imuBias::ConstantBias &biasHat=imuBias::ConstantBias())
 
void resetIntegration () override
 
NavState deltaXij () const override
 
Rot3 deltaRij () const override
 
Vector3 deltaPij () const override
 
Vector3 deltaVij () const override
 
Matrix3 delRdelBiasOmega () const
 
Matrix3 delPdelBiasAcc () const
 
Matrix3 delPdelBiasOmega () const
 
Matrix3 delVdelBiasAcc () const
 
Matrix3 delVdelBiasOmega () const
 
bool equals (const ManifoldPreintegration &other, double tol) const
 
void update (const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt, Matrix9 *A, Matrix93 *B, Matrix93 *C) override
 
Vector9 biasCorrectedDelta (const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 6 > H={}) const override
 
virtual std::shared_ptr< ManifoldPreintegrationclone () const
 
- Public Member Functions inherited from gtsam::PreintegrationBase
 PreintegrationBase (const std::shared_ptr< Params > &p, const imuBias::ConstantBias &biasHat=imuBias::ConstantBias())
 
void resetIntegrationAndSetBias (const Bias &biasHat)
 
bool matchesParamsWith (const PreintegrationBase &other) const
 check parameters equality: checks whether shared pointer points to same Params object. More...
 
const std::shared_ptr< Params > & params () const
 shared pointer to params More...
 
Paramsp () const
 const reference to params More...
 
const imuBias::ConstantBiasbiasHat () const
 
double deltaTij () const
 
Vector6 biasHatVector () const
 
std::pair< Vector3, Vector3correctMeasurementsBySensorPose (const Vector3 &unbiasedAcc, const Vector3 &unbiasedOmega, OptionalJacobian< 3, 3 > correctedAcc_H_unbiasedAcc={}, OptionalJacobian< 3, 3 > correctedAcc_H_unbiasedOmega={}, OptionalJacobian< 3, 3 > correctedOmega_H_unbiasedOmega={}) const
 
NavState predict (const NavState &state_i, const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 9 > H1={}, OptionalJacobian< 9, 6 > H2={}) const
 Predict state at time j. More...
 
Vector9 computeError (const NavState &state_i, const NavState &state_j, const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 9 > H1, OptionalJacobian< 9, 9 > H2, OptionalJacobian< 9, 6 > H3) const
 Calculate error given navStates. More...
 
Vector9 computeErrorAndJacobians (const Pose3 &pose_i, const Vector3 &vel_i, const Pose3 &pose_j, const Vector3 &vel_j, const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 6 > H1={}, OptionalJacobian< 9, 3 > H2={}, OptionalJacobian< 9, 6 > H3={}, OptionalJacobian< 9, 3 > H4={}, OptionalJacobian< 9, 6 > H5={}) const
 

Protected Attributes

Matrix9 preintMeasCov_
 (first-order propagation from measurementCovariance). More...
 
- Protected Attributes inherited from gtsam::ManifoldPreintegration
Matrix3 delPdelBiasAcc_
 Jacobian of preintegrated position w.r.t. acceleration bias. More...
 
Matrix3 delPdelBiasOmega_
 Jacobian of preintegrated position w.r.t. angular rate bias. More...
 
Matrix3 delRdelBiasOmega_
 Jacobian of preintegrated rotation w.r.t. angular rate bias. More...
 
NavState deltaXij_
 
Matrix3 delVdelBiasAcc_
 Jacobian of preintegrated velocity w.r.t. acceleration bias. More...
 
Matrix3 delVdelBiasOmega_
 Jacobian of preintegrated velocity w.r.t. angular rate bias. More...
 
- Protected Attributes inherited from gtsam::PreintegrationBase
Bias biasHat_
 Acceleration and gyro bias used for preintegration. More...
 
double deltaTij_
 Time interval from i to j. More...
 
std::shared_ptr< Paramsp_
 

Friends

class ImuFactor
 
class ImuFactor2
 

Additional Inherited Members

- Public Types inherited from gtsam::PreintegrationBase
typedef imuBias::ConstantBias Bias
 
typedef PreintegrationParams Params
 
- Protected Member Functions inherited from gtsam::ManifoldPreintegration
 ManifoldPreintegration ()
 Default constructor for serialization. More...
 
- Protected Member Functions inherited from gtsam::PreintegrationBase
 PreintegrationBase ()
 Default constructor for serialization. More...
 
virtual ~PreintegrationBase ()
 Virtual destructor for serialization. More...
 

Detailed Description

PreintegratedImuMeasurements accumulates (integrates) the IMU measurements (rotation rates and accelerations) and the corresponding covariance matrix. The measurements are then used to build the Preintegrated IMU factor. Integration is done incrementally (ideally, one integrates the measurement as soon as it is received from the IMU) so as to avoid costly integration at time of factor construction.

Definition at line 72 of file ImuFactor.h.

Constructor & Destructor Documentation

◆ PreintegratedImuMeasurements() [1/3]

gtsam::PreintegratedImuMeasurements::PreintegratedImuMeasurements ( )
inline

Default constructor for serialization and wrappers.

Definition at line 85 of file ImuFactor.h.

◆ PreintegratedImuMeasurements() [2/3]

gtsam::PreintegratedImuMeasurements::PreintegratedImuMeasurements ( const std::shared_ptr< PreintegrationParams > &  p,
const imuBias::ConstantBias biasHat = imuBias::ConstantBias() 
)
inline

Constructor, initializes the class with no measurements

Parameters
pParameters, typically fixed in a single application
biasHatCurrent estimate of acceleration and rotation rate biases

Definition at line 94 of file ImuFactor.h.

◆ PreintegratedImuMeasurements() [3/3]

gtsam::PreintegratedImuMeasurements::PreintegratedImuMeasurements ( const PreintegrationType base,
const Matrix9 preintMeasCov 
)
inline

Construct preintegrated directly from members: base class and preintMeasCov

Parameters
basePreintegrationType instance
preintMeasCovCovariance matrix used in noise model.

Definition at line 105 of file ImuFactor.h.

◆ ~PreintegratedImuMeasurements()

gtsam::PreintegratedImuMeasurements::~PreintegratedImuMeasurements ( )
inlineoverride

Virtual destructor.

Definition at line 111 of file ImuFactor.h.

Member Function Documentation

◆ equals()

bool gtsam::PreintegratedImuMeasurements::equals ( const PreintegratedImuMeasurements expected,
double  tol = 1e-9 
) const

equals

Definition at line 40 of file ImuFactor.cpp.

◆ integrateMeasurement()

void gtsam::PreintegratedImuMeasurements::integrateMeasurement ( const Vector3 measuredAcc,
const Vector3 measuredOmega,
const double  dt 
)
overridevirtual

Add a single IMU measurement to the preintegration. Both accelerometer and gyroscope measurements are taken to be in the sensor frame and conversion to the body frame is handled by body_P_sensor in PreintegrationParams.

Parameters
measuredAccMeasured acceleration (as given by the sensor)
measuredOmegaMeasured angular velocity (as given by the sensor)
dtTime interval between this and the last IMU measurement

Reimplemented from gtsam::PreintegrationBase.

Definition at line 53 of file ImuFactor.cpp.

◆ integrateMeasurements()

void gtsam::PreintegratedImuMeasurements::integrateMeasurements ( const Matrix measuredAccs,
const Matrix measuredOmegas,
const Matrix dts 
)

Add multiple measurements, in matrix columns.

Definition at line 87 of file ImuFactor.cpp.

◆ preintMeasCov()

Matrix gtsam::PreintegratedImuMeasurements::preintMeasCov ( ) const
inline

Return pre-integrated measurement covariance.

Definition at line 141 of file ImuFactor.h.

◆ print()

void gtsam::PreintegratedImuMeasurements::print ( const std::string &  s = "Preintegrated Measurements:") const
overridevirtual

print

Reimplemented from gtsam::PreintegrationBase.

Definition at line 34 of file ImuFactor.cpp.

◆ resetIntegration()

void gtsam::PreintegratedImuMeasurements::resetIntegration ( )
overridevirtual

Re-initialize PreintegratedIMUMeasurements.

Implements gtsam::PreintegrationBase.

Definition at line 47 of file ImuFactor.cpp.

Friends And Related Function Documentation

◆ ImuFactor

friend class ImuFactor
friend

Definition at line 74 of file ImuFactor.h.

◆ ImuFactor2

friend class ImuFactor2
friend

Definition at line 75 of file ImuFactor.h.

Member Data Documentation

◆ preintMeasCov_

Matrix9 gtsam::PreintegratedImuMeasurements::preintMeasCov_
protected

(first-order propagation from measurementCovariance).

COVARIANCE OF: [PreintROTATION PreintPOSITION PreintVELOCITY]

Definition at line 79 of file ImuFactor.h.


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


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:47:07