gtsam 4.1.1
gtsam
gtsam::PreintegratedImuMeasurements Class Reference
+ Inheritance diagram for gtsam::PreintegratedImuMeasurements:

Public Member Functions

 PreintegratedImuMeasurements ()
 Default constructor for serialization and wrappers.
 
 PreintegratedImuMeasurements (const boost::shared_ptr< PreintegrationParams > &p, const imuBias::ConstantBias &biasHat=imuBias::ConstantBias())
 Constructor, initializes the class with no measurements. More...
 
 PreintegratedImuMeasurements (const PreintegrationType &base, const Matrix9 &preintMeasCov)
 Construct preintegrated directly from members: base class and preintMeasCov. More...
 
 ~PreintegratedImuMeasurements () override
 Virtual destructor.
 
void print (const std::string &s="Preintegrated Measurements:") const override
 print More...
 
bool equals (const PreintegratedImuMeasurements &expected, double tol=1e-9) const
 equals
 
void resetIntegration () override
 Re-initialize PreintegratedIMUMeasurements. More...
 
void integrateMeasurement (const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt) override
 Add a single IMU measurement to the preintegration. More...
 
void integrateMeasurements (const Matrix &measuredAccs, const Matrix &measuredOmegas, const Matrix &dts)
 Add multiple measurements, in matrix columns.
 
Matrix preintMeasCov () const
 Return pre-integrated measurement covariance.
 
- Public Member Functions inherited from gtsam::ManifoldPreintegration
 ManifoldPreintegration (const boost::shared_ptr< Params > &p, const imuBias::ConstantBias &biasHat=imuBias::ConstantBias())
 Constructor, initializes the variables in the base class. More...
 
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
 Update preintegrated measurements and get derivatives It takes measured quantities in the j frame Modifies preintegrated quantities in place after correcting for bias and possibly sensor pose NOTE(frank): implementation is different in two versions. More...
 
Vector9 biasCorrectedDelta (const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 6 > H=boost::none) const override
 Given the estimate of the bias, return a NavState tangent vector summarizing the preintegrated IMU measurements so far NOTE(frank): implementation is different in two versions. More...
 
virtual boost::shared_ptr< ManifoldPreintegrationclone () const
 Dummy clone for MATLAB.
 
- Public Member Functions inherited from gtsam::PreintegrationBase
 PreintegrationBase (const boost::shared_ptr< Params > &p, const imuBias::ConstantBias &biasHat=imuBias::ConstantBias())
 Constructor, initializes the variables in the base class. More...
 
void resetIntegrationAndSetBias (const Bias &biasHat)
 
bool matchesParamsWith (const PreintegrationBase &other) const
 check parameters equality: checks whether shared pointer points to same Params object.
 
const boost::shared_ptr< Params > & params () const
 shared pointer to params
 
Paramsp () const
 const reference to params
 
const imuBias::ConstantBiasbiasHat () const
 
double deltaTij () const
 
Vector6 biasHatVector () const
 
std::pair< Vector3, Vector3 > correctMeasurementsBySensorPose (const Vector3 &unbiasedAcc, const Vector3 &unbiasedOmega, OptionalJacobian< 3, 3 > correctedAcc_H_unbiasedAcc=boost::none, OptionalJacobian< 3, 3 > correctedAcc_H_unbiasedOmega=boost::none, OptionalJacobian< 3, 3 > correctedOmega_H_unbiasedOmega=boost::none) const
 Subtract estimate and correct for sensor pose Compute the derivatives due to non-identity body_P_sensor (rotation and centrifugal acc) Ignore D_correctedOmega_measuredAcc as it is trivially zero.
 
NavState predict (const NavState &state_i, const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 9 > H1=boost::none, OptionalJacobian< 9, 6 > H2=boost::none) const
 Predict state at time j.
 
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.
 
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=boost::none, OptionalJacobian< 9, 3 > H2=boost::none, OptionalJacobian< 9, 6 > H3=boost::none, OptionalJacobian< 9, 3 > H4=boost::none, OptionalJacobian< 9, 6 > H5=boost::none) const
 Compute errors w.r.t. More...
 

Protected Attributes

Matrix9 preintMeasCov_
 COVARIANCE OF: [PreintROTATION PreintPOSITION PreintVELOCITY]. More...
 
- Protected Attributes inherited from gtsam::ManifoldPreintegration
NavState deltaXij_
 Pre-integrated navigation state, from frame i to frame j Note: relative position does not take into account velocity at time i, see deltap+, in [2] Note: velocity is now also in frame i, as opposed to deltaVij in [2].
 
Matrix3 delRdelBiasOmega_
 Jacobian of preintegrated rotation w.r.t. angular rate bias.
 
Matrix3 delPdelBiasAcc_
 Jacobian of preintegrated position w.r.t. acceleration bias.
 
Matrix3 delPdelBiasOmega_
 Jacobian of preintegrated position w.r.t. angular rate bias.
 
Matrix3 delVdelBiasAcc_
 Jacobian of preintegrated velocity w.r.t. acceleration bias.
 
Matrix3 delVdelBiasOmega_
 Jacobian of preintegrated velocity w.r.t. angular rate bias.
 
- Protected Attributes inherited from gtsam::PreintegrationBase
boost::shared_ptr< Paramsp_
 
Bias biasHat_
 Acceleration and gyro bias used for preintegration.
 
double deltaTij_
 Time interval from i to j.
 

Friends

class ImuFactor
 
class ImuFactor2
 
class boost::serialization::access
 Serialization function.
 

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.
 
- Protected Member Functions inherited from gtsam::PreintegrationBase
 PreintegrationBase ()
 Default constructor for serialization.
 
virtual ~PreintegrationBase ()
 Virtual destructor for serialization.
 

Constructor & Destructor Documentation

◆ PreintegratedImuMeasurements() [1/2]

gtsam::PreintegratedImuMeasurements::PreintegratedImuMeasurements ( const boost::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

◆ PreintegratedImuMeasurements() [2/2]

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.

Member Function Documentation

◆ integrateMeasurement()

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

Add a single IMU measurement to the preintegration.

Parameters
measuredAccMeasured acceleration (in body frame, 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.

◆ print()

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

print

Reimplemented from gtsam::PreintegrationBase.

◆ resetIntegration()

void gtsam::PreintegratedImuMeasurements::resetIntegration ( )
overridevirtual

Re-initialize PreintegratedIMUMeasurements.

Implements gtsam::PreintegrationBase.

Member Data Documentation

◆ preintMeasCov_

Matrix9 gtsam::PreintegratedImuMeasurements::preintMeasCov_
protected

COVARIANCE OF: [PreintROTATION PreintPOSITION PreintVELOCITY].

(first-order propagation from measurementCovariance).


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