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

#include <AHRSFactor.h>

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

Public Member Functions

const Vector3biasHat () const
 
bool equals (const PreintegratedAhrsMeasurements &, double tol=1e-9) const
 equals More...
 
void integrateMeasurement (const Vector3 &measuredOmega, double deltaT)
 
Paramsp () const
 
Vector3 predict (const Vector3 &bias, OptionalJacobian< 3, 3 > H={}) const
 
 PreintegratedAhrsMeasurements ()
 Default constructor, only for serialization and wrappers. More...
 
 PreintegratedAhrsMeasurements (const std::shared_ptr< Params > &p, const Vector3 &bias_hat, double deltaTij, const Rot3 &deltaRij, const Matrix3 &delRdelBiasOmega, const Matrix3 &preint_meas_cov)
 
 PreintegratedAhrsMeasurements (const std::shared_ptr< Params > &p, const Vector3 &biasHat)
 
 PreintegratedAhrsMeasurements (const Vector3 &biasHat, const Matrix3 &measuredOmegaCovariance)
 
const Matrix3 & preintMeasCov () const
 
void print (const std::string &s="Preintegrated Measurements: ") const
 print More...
 
void resetIntegration ()
 Reset inetgrated quantities to zero. More...
 
- Public Member Functions inherited from gtsam::PreintegratedRotation
 PreintegratedRotation (const std::shared_ptr< Params > &p)
 Default constructor, resets integration to zero. More...
 
 PreintegratedRotation (const std::shared_ptr< Params > &p, double deltaTij, const Rot3 &deltaRij, const Matrix3 &delRdelBiasOmega)
 Explicit initialization of all class members. More...
 
void resetIntegration ()
 Re-initialize PreintegratedMeasurements. More...
 
bool matchesParamsWith (const PreintegratedRotation &other) const
 check parameters equality: checks whether shared pointer points to same Params object. More...
 
const std::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
 
void integrateGyroMeasurement (const Vector3 &measuredOmega, const Vector3 &biasHat, double deltaT, OptionalJacobian< 3, 3 > F={})
 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={}) const
 Return a bias corrected version of the integrated rotation. More...
 
Vector3 integrateCoriolis (const Rot3 &rot_i) const
 Integrate coriolis correction in body frame rot_i. More...
 

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. More...
 
Matrix3 preintMeasCov_
 Covariance matrix of the preintegrated measurements (first-order propagation from measurementCovariance) More...
 
- Protected Attributes inherited from gtsam::PreintegratedRotation
Matrix3 delRdelBiasOmega_
 Jacobian of preintegrated rotation w.r.t. angular rate bias. More...
 
Rot3 deltaRij_
 Preintegrated relative orientation (in frame i) More...
 
double deltaTij_
 Time interval from i to j. More...
 
std::shared_ptr< Paramsp_
 Parameters. More...
 

Friends

class AHRSFactor
 

Additional Inherited Members

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

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.

Definition at line 36 of file AHRSFactor.h.

Constructor & Destructor Documentation

◆ PreintegratedAhrsMeasurements() [1/4]

gtsam::PreintegratedAhrsMeasurements::PreintegratedAhrsMeasurements ( )
inline

Default constructor, only for serialization and wrappers.

Definition at line 48 of file AHRSFactor.h.

◆ PreintegratedAhrsMeasurements() [2/4]

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

Default constructor, initialize with no measurements

Parameters
biasCurrent estimate of acceleration and rotation rate biases

Definition at line 54 of file AHRSFactor.h.

◆ PreintegratedAhrsMeasurements() [3/4]

gtsam::PreintegratedAhrsMeasurements::PreintegratedAhrsMeasurements ( const std::shared_ptr< Params > &  p,
const Vector3 bias_hat,
double  deltaTij,
const Rot3 deltaRij,
const Matrix3 &  delRdelBiasOmega,
const Matrix3 &  preint_meas_cov 
)
inline

Non-Default constructor, initialize with measurements

Parameters
pParameters for AHRS pre-integration
bias_hatCurrent estimate of acceleration and rotation rate biases
deltaTijDelta time in pre-integration
deltaRijDelta rotation in pre-integration
delRdelBiasOmegaJacobian of rotation wrt. to gyro bias
preint_meas_covPre-integration covariance

Definition at line 69 of file AHRSFactor.h.

◆ PreintegratedAhrsMeasurements() [4/4]

gtsam::PreintegratedAhrsMeasurements::PreintegratedAhrsMeasurements ( const Vector3 biasHat,
const Matrix3 &  measuredOmegaCovariance 
)
inline
Deprecated:
constructor, but used in tests.

Definition at line 114 of file AHRSFactor.h.

Member Function Documentation

◆ biasHat()

const Vector3& gtsam::PreintegratedAhrsMeasurements::biasHat ( ) const
inline

Definition at line 81 of file AHRSFactor.h.

◆ DeltaAngles()

Vector gtsam::PreintegratedAhrsMeasurements::DeltaAngles ( const Vector msr_gyro_t,
const double  msr_dt,
const Vector3 delta_angles 
)
static

Definition at line 74 of file AHRSFactor.cpp.

◆ equals()

bool gtsam::PreintegratedAhrsMeasurements::equals ( const PreintegratedAhrsMeasurements other,
double  tol = 1e-9 
) const

equals

Definition at line 37 of file AHRSFactor.cpp.

◆ integrateMeasurement()

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

Add a single Gyroscope measurement to the preintegration. Measurements are taken to be in the sensor frame and conversion to the body frame is handled by body_P_sensor in PreintegratedRotationParams (if provided).

Parameters
measuredOmegaMeasured angular velocity (as given by the sensor)
deltaTTime step

Definition at line 50 of file AHRSFactor.cpp.

◆ p()

Params& gtsam::PreintegratedAhrsMeasurements::p ( ) const
inline

Definition at line 80 of file AHRSFactor.h.

◆ predict()

Vector3 gtsam::PreintegratedAhrsMeasurements::predict ( const Vector3 bias,
OptionalJacobian< 3, 3 >  H = {} 
) const

Predict bias-corrected incremental rotation TODO: The matrix Hbias is the derivative of predict? Unit-test?

Definition at line 64 of file AHRSFactor.cpp.

◆ preintMeasCov()

const Matrix3& gtsam::PreintegratedAhrsMeasurements::preintMeasCov ( ) const
inline

Definition at line 82 of file AHRSFactor.h.

◆ print()

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

print

Definition at line 30 of file AHRSFactor.cpp.

◆ resetIntegration()

void gtsam::PreintegratedAhrsMeasurements::resetIntegration ( )

Reset inetgrated quantities to zero.

Definition at line 44 of file AHRSFactor.cpp.

Friends And Related Function Documentation

◆ AHRSFactor

friend class AHRSFactor
friend

Definition at line 43 of file AHRSFactor.h.

Member Data Documentation

◆ biasHat_

Vector3 gtsam::PreintegratedAhrsMeasurements::biasHat_
protected

Angular rate bias values used during preintegration.

Definition at line 40 of file AHRSFactor.h.

◆ preintMeasCov_

Matrix3 gtsam::PreintegratedAhrsMeasurements::preintMeasCov_
protected

Covariance matrix of the preintegrated measurements (first-order propagation from measurementCovariance)

Definition at line 41 of file AHRSFactor.h.


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


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:16:25