GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
Public Types | Protected Member Functions | Protected Attributes | List of all members
gtsam::ManifoldPreintegration Class Reference

#include <ManifoldPreintegration.h>

Inheritance diagram for gtsam::ManifoldPreintegration:
Inheritance graph
[legend]
Collaboration diagram for gtsam::ManifoldPreintegration:
Collaboration graph
[legend]

Public Types

typedef imuBias::ConstantBias Bias
 
typedef PreintegrationParams Params
 

Public Member Functions

Constructors
 ManifoldPreintegration (const std::shared_ptr< Params > &p, const imuBias::ConstantBias &biasHat=imuBias::ConstantBias())
 
Basic utilities

Re-initialize PreintegratedMeasurements

void resetIntegration () override
 
Instance variables access
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
 
Testable
bool equals (const ManifoldPreintegration &other, double tol) const
 
Main functionality
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
 
Basic utilities

Re-initialize PreintegratedMeasurements and set new bias

void resetIntegrationAndSetBias (const Bias &biasHat)
 
bool matchesParamsWith (const PreintegrationBase &other) const
 check parameters equality: checks whether shared pointer points to same Params object.
 
const std::shared_ptr< Params > & params () const
 shared pointer to params
 
Paramsp () const
 const reference to params
 
Instance variables access
const imuBias::ConstantBiasbiasHat () const
 
double deltaTij () const
 
Vector6 biasHatVector () const
 
Testable
virtual void print (const std::string &s="") const
 
Main functionality
std::pair< Vector3, Vector3 > correctMeasurementsBySensorPose (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
 
virtual void integrateMeasurement (const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt)
 Version without derivatives.
 
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.
 
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={}, OptionalJacobian< 9, 3 > H2={}, OptionalJacobian< 9, 6 > H3={}, OptionalJacobian< 9, 3 > H4={}, OptionalJacobian< 9, 6 > H5={}) const
 

Protected Member Functions

 ManifoldPreintegration ()
 Default constructor for serialization.
 

Protected Attributes

NavState deltaXij_
 
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.
 
std::shared_ptr< Paramsp_
 
Bias biasHat_
 Acceleration and gyro bias used for preintegration.
 
double deltaTij_
 Time interval from i to j.
 

Detailed Description

IMU pre-integration on NavSatet manifold. This corresponds to the original RSS paper (with one difference: V is rotated)

Constructor & Destructor Documentation

◆ ManifoldPreintegration()

gtsam::ManifoldPreintegration::ManifoldPreintegration ( const std::shared_ptr< Params > &  p,
const imuBias::ConstantBias biasHat = imuBias::ConstantBias() 
)

Constructor, initializes the variables in the base class

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

Member Function Documentation

◆ biasCorrectedDelta()

Vector9 gtsam::ManifoldPreintegration::biasCorrectedDelta ( const imuBias::ConstantBias bias_i,
OptionalJacobian< 9, 6 >  H = {} 
) const
overridevirtual

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

Implements gtsam::PreintegrationBase.

◆ clone()

virtual std::shared_ptr<ManifoldPreintegration> gtsam::ManifoldPreintegration::clone ( ) const
inlinevirtual

Dummy clone for MATLAB

◆ computeErrorAndJacobians()

Vector9 gtsam::PreintegrationBase::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
inherited

Compute errors w.r.t. preintegrated measurements and jacobians wrt pose_i, vel_i, bias_i, pose_j, bias_j

◆ correctMeasurementsBySensorPose()

std::pair<Vector3, Vector3> gtsam::PreintegrationBase::correctMeasurementsBySensorPose ( 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
inherited

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

◆ update()

void gtsam::ManifoldPreintegration::update ( const Vector3 &  measuredAcc,
const Vector3 &  measuredOmega,
const double  dt,
Matrix9 *  A,
Matrix93 *  B,
Matrix93 *  C 
)
overridevirtual

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

Implements gtsam::PreintegrationBase.

Member Data Documentation

◆ deltaXij_

NavState gtsam::ManifoldPreintegration::deltaXij_
protected

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]


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