gtsam  4.0.0
gtsam
gtsam::PreintegratedAhrsMeasurements Class Reference

Detailed Description

PreintegratedAHRSMeasurements accumulates (integrates) the Gyroscope measurements (rotation rates) and the corresponding covariance matrix.

Can be built incrementally so as to avoid costly integration at time of factor construction.

+ Inheritance diagram for gtsam::PreintegratedAhrsMeasurements:

Public Member Functions

 PreintegratedAhrsMeasurements ()
 Default constructor, only for serialization and Cython wrapper.
 
 PreintegratedAhrsMeasurements (const boost::shared_ptr< Params > &p, const Vector3 &biasHat)
 Default constructor, initialize with no measurements. More...
 
const Paramsp () const
 
const Vector3 & biasHat () const
 
const Matrix3 & preintMeasCov () const
 
void print (const std::string &s="Preintegrated Measurements: ") const
 print
 
bool equals (const PreintegratedAhrsMeasurements &, double tol=1e-9) const
 equals
 
void resetIntegration ()
 Reset inetgrated quantities to zero.
 
void integrateMeasurement (const Vector3 &measuredOmega, double deltaT)
 Add a single Gyroscope measurement to the preintegration. More...
 
Vector3 predict (const Vector3 &bias, OptionalJacobian< 3, 3 > H=boost::none) const
 Predict bias-corrected incremental rotation TODO: The matrix Hbias is the derivative of predict? Unit-test?
 
 PreintegratedAhrsMeasurements (const Vector3 &biasHat, const Matrix3 &measuredOmegaCovariance)
 
- Public Member Functions inherited from gtsam::PreintegratedRotation
 PreintegratedRotation (const boost::shared_ptr< Params > &p)
 Default constructor, resets integration to zero.
 
 PreintegratedRotation (const boost::shared_ptr< Params > &p, double deltaTij, const Rot3 &deltaRij, const Matrix3 &delRdelBiasOmega)
 Explicit initialization of all class members.
 
void resetIntegration ()
 Re-initialize PreintegratedMeasurements.
 
bool matchesParamsWith (const PreintegratedRotation &other) const
 check parameters equality: checks whether shared pointer points to same Params object.
 
const boost::shared_ptr< Params > & params () const
 
const double & deltaTij () const
 
const Rot3deltaRij () const
 
const Matrix3 & delRdelBiasOmega () const
 
void print (const std::string &s) const
 
bool equals (const PreintegratedRotation &other, double tol) const
 
Rot3 incrementalRotation (const Vector3 &measuredOmega, const Vector3 &biasHat, double deltaT, OptionalJacobian< 3, 3 > D_incrR_integratedOmega) const
 Take the gyro measurement, correct it using the (constant) bias estimate and possibly the sensor pose, and then integrate it forward in time to yield an incremental rotation. More...
 
void integrateMeasurement (const Vector3 &measuredOmega, const Vector3 &biasHat, double deltaT, OptionalJacobian< 3, 3 > D_incrR_integratedOmega=boost::none, OptionalJacobian< 3, 3 > F=boost::none)
 Calculate an incremental rotation given the gyro measurement and a time interval, and update both deltaTij_ and deltaRij_. More...
 
Rot3 biascorrectedDeltaRij (const Vector3 &biasOmegaIncr, OptionalJacobian< 3, 3 > H=boost::none) const
 Return a bias corrected version of the integrated rotation, with optional Jacobian.
 
Vector3 integrateCoriolis (const Rot3 &rot_i) const
 Integrate coriolis correction in body frame rot_i.
 

Static Public Member Functions

static Vector DeltaAngles (const Vector &msr_gyro_t, const double msr_dt, const Vector3 &delta_angles)
 

Protected Attributes

Vector3 biasHat_
 Angular rate bias values used during preintegration.
 
Matrix3 preintMeasCov_
 Covariance matrix of the preintegrated measurements (first-order propagation from measurementCovariance)
 
- Protected Attributes inherited from gtsam::PreintegratedRotation
boost::shared_ptr< Paramsp_
 Parameters.
 
double deltaTij_
 Time interval from i to j.
 
Rot3 deltaRij_
 Preintegrated relative orientation (in frame i)
 
Matrix3 delRdelBiasOmega_
 Jacobian of preintegrated rotation w.r.t. angular rate bias.
 

Friends

class AHRSFactor
 
class boost::serialization::access
 Serialization function.
 

Additional Inherited Members

- Public Types inherited from gtsam::PreintegratedRotation
typedef PreintegratedRotationParams Params
 
- Protected Member Functions inherited from gtsam::PreintegratedRotation
 PreintegratedRotation ()
 Default constructor for serialization.
 

Constructor & Destructor Documentation

◆ PreintegratedAhrsMeasurements() [1/2]

gtsam::PreintegratedAhrsMeasurements::PreintegratedAhrsMeasurements ( const boost::shared_ptr< Params > &  p,
const Vector3 &  biasHat 
)
inline

Default constructor, initialize with no measurements.

Parameters
biasCurrent estimate of acceleration and rotation rate biases

◆ PreintegratedAhrsMeasurements() [2/2]

gtsam::PreintegratedAhrsMeasurements::PreintegratedAhrsMeasurements ( const Vector3 &  biasHat,
const Matrix3 &  measuredOmegaCovariance 
)
inline
Deprecated:
constructor

Member Function Documentation

◆ integrateMeasurement()

void gtsam::PreintegratedAhrsMeasurements::integrateMeasurement ( const Vector3 &  measuredOmega,
double  deltaT 
)

Add a single Gyroscope measurement to the preintegration.

Parameters
measureOmedgaMeasured angular velocity (in body frame)
deltaTTime step

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