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

#include <TangentPreintegration.h>

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

Public Types

typedef imuBias::ConstantBias Bias
 
typedef PreintegrationParams Params
 

Public Member Functions

virtual std::shared_ptr< TangentPreintegrationclone () const
 
Constructors/destructors
 TangentPreintegration (const std::shared_ptr< Params > &p, const imuBias::ConstantBias &biasHat=imuBias::ConstantBias())
 
 ~TangentPreintegration () override
 Virtual destructor.
 
Basic utilities

Re-initialize PreintegratedMeasurements

void resetIntegration () override
 
Instance variables access
Vector3 deltaPij () const override
 
Vector3 deltaVij () const override
 
Rot3 deltaRij () const override
 
NavState deltaXij () const override
 
const Vector9 & preintegrated () const
 
Vector3 theta () const
 
const Matrix93 & preintegrated_H_biasAcc () const
 
const Matrix93 & preintegrated_H_biasOmega () const
 
Testable
bool equals (const TangentPreintegration &other, double tol) 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

 TangentPreintegration ()
 Default constructor for serialization.
 

Protected Attributes

Vector9 preintegrated_
 
Matrix93 preintegrated_H_biasAcc_
 Jacobian of preintegrated_ w.r.t. acceleration bias.
 
Matrix93 preintegrated_H_biasOmega_
 Jacobian of preintegrated_ 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.
 

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
 
void mergeWith (const TangentPreintegration &pim, Matrix9 *H1, Matrix9 *H2)
 
static Vector9 UpdatePreintegrated (const Vector3 &a_body, const Vector3 &w_body, const double dt, const Vector9 &preintegrated, OptionalJacobian< 9, 9 > A={}, OptionalJacobian< 9, 3 > B={}, OptionalJacobian< 9, 3 > C={})
 
static Vector9 Compose (const Vector9 &zeta01, const Vector9 &zeta12, double deltaT12, OptionalJacobian< 9, 9 > H1={}, OptionalJacobian< 9, 9 > H2={})
 

Detailed Description

Integrate on the 9D tangent space of the NavState manifold. See extensive discussion in ImuFactor.lyx

Constructor & Destructor Documentation

◆ TangentPreintegration()

gtsam::TangentPreintegration::TangentPreintegration ( 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::TangentPreintegration::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<TangentPreintegration> gtsam::TangentPreintegration::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

◆ mergeWith()

void gtsam::TangentPreintegration::mergeWith ( const TangentPreintegration pim,
Matrix9 *  H1,
Matrix9 *  H2 
)

Merge in a different set of measurements and update bias derivatives accordingly The derivatives apply to the preintegrated Vector9

◆ update()

void gtsam::TangentPreintegration::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

◆ preintegrated_

Vector9 gtsam::TangentPreintegration::preintegrated_
protected

Preintegrated navigation state, as a 9D vector on tangent space at frame i Order is: theta, position, velocity


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