|
GTSAM
4.0.2
C++ library for smoothing and mapping (SAM)
|
#include <AHRSFactor.h>


Public Types | |
| typedef PreintegratedRotationParams | Params |
Public Member Functions | |
| PreintegratedAhrsMeasurements () | |
| Default constructor, only for serialization and wrappers. | |
| PreintegratedAhrsMeasurements (const std::shared_ptr< Params > &p, const Vector3 &biasHat) | |
| PreintegratedAhrsMeasurements (const std::shared_ptr< Params > &p, const Vector3 &bias_hat, double deltaTij, const Rot3 &deltaRij, const Matrix3 &delRdelBiasOmega, const Matrix3 &preint_meas_cov) | |
| Params & | p () 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) |
| Vector3 | predict (const Vector3 &bias, OptionalJacobian< 3, 3 > H={}) const |
| PreintegratedAhrsMeasurements (const Vector3 &biasHat, const Matrix3 &measuredOmegaCovariance) | |
Basic utilities | |
| bool | matchesParamsWith (const PreintegratedRotation &other) const |
| check parameters equality: checks whether shared pointer points to same Params object. | |
Access instance variables | |
| const std::shared_ptr< Params > & | params () const |
| const double & | deltaTij () const |
| const Rot3 & | deltaRij () const |
| const Matrix3 & | delRdelBiasOmega () const |
Testable | |
| bool | equals (const PreintegratedRotation &other, double tol) const |
Main functionality | |
| Rot3 | incrementalRotation (const Vector3 &measuredOmega, const Vector3 &biasHat, double deltaT, OptionalJacobian< 3, 3 > D_incrR_integratedOmega) const |
| void | integrateMeasurement (const Vector3 &measuredOmega, const Vector3 &biasHat, double deltaT, OptionalJacobian< 3, 3 > D_incrR_integratedOmega={}, OptionalJacobian< 3, 3 > F={}) |
| Rot3 | biascorrectedDeltaRij (const Vector3 &biasOmegaIncr, OptionalJacobian< 3, 3 > H={}) 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) | |
| std::shared_ptr< Params > | p_ |
| 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 |
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.
|
inline |
Default constructor, initialize with no measurements
| bias | Current estimate of acceleration and rotation rate biases |
|
inline |
Non-Default constructor, initialize with measurements
| p | Parameters for AHRS pre-integration |
| bias_hat | Current estimate of acceleration and rotation rate biases |
| deltaTij | Delta time in pre-integration |
| deltaRij | Delta rotation in pre-integration |
| delRdelBiasOmega | Jacobian of rotation wrt. to gyro bias |
| preint_meas_cov | Pre-integration covariance |
|
inline |
|
inherited |
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.
| 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).
| measuredOmega | Measured angular velocity (as given by the sensor) |
| deltaT | Time step |
|
inherited |
Calculate an incremental rotation given the gyro measurement and a time interval, and update both deltaTij_ and deltaRij_.
| 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?
1.8.13