#include <AHRSFactor.h>
Public Member Functions | |
const Vector3 & | biasHat () const |
bool | equals (const PreintegratedAhrsMeasurements &, double tol=1e-9) const |
equals More... | |
void | integrateMeasurement (const Vector3 &measuredOmega, double deltaT) |
Params & | p () const |
Vector3 | predict (const Vector3 &bias, OptionalJacobian< 3, 3 > H=boost::none) const |
PreintegratedAhrsMeasurements () | |
Default constructor, only for serialization and wrappers. More... | |
PreintegratedAhrsMeasurements (const boost::shared_ptr< Params > &p, const Vector3 &biasHat) | |
PreintegratedAhrsMeasurements (const boost::shared_ptr< Params > &p, const Vector3 &bias_hat, double deltaTij, const Rot3 &deltaRij, const Matrix3 &delRdelBiasOmega, const Matrix3 &preint_meas_cov) | |
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 boost::shared_ptr< Params > &p) | |
Default constructor, resets integration to zero. More... | |
PreintegratedRotation (const boost::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 boost::shared_ptr< Params > & | params () const |
const double & | deltaTij () const |
const Rot3 & | deltaRij () 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 |
void | integrateMeasurement (const Vector3 &measuredOmega, const Vector3 &biasHat, double deltaT, OptionalJacobian< 3, 3 > D_incrR_integratedOmega=boost::none, OptionalJacobian< 3, 3 > F=boost::none) |
Rot3 | biascorrectedDeltaRij (const Vector3 &biasOmegaIncr, OptionalJacobian< 3, 3 > H=boost::none) const |
Return a bias corrected version of the integrated rotation, with optional Jacobian. 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... | |
boost::shared_ptr< Params > | p_ |
Parameters. More... | |
Private Member Functions | |
template<class ARCHIVE > | |
void | serialize (ARCHIVE &ar, const unsigned int) |
Friends | |
class | AHRSFactor |
class | boost::serialization::access |
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... | |
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 34 of file AHRSFactor.h.
|
inline |
Default constructor, only for serialization and wrappers.
Definition at line 46 of file AHRSFactor.h.
|
inline |
Default constructor, initialize with no measurements
bias | Current estimate of acceleration and rotation rate biases |
Definition at line 52 of file AHRSFactor.h.
|
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 |
Definition at line 67 of file AHRSFactor.h.
|
inline |
Definition at line 108 of file AHRSFactor.h.
|
inline |
Definition at line 79 of file AHRSFactor.h.
|
static |
Definition at line 73 of file AHRSFactor.cpp.
bool gtsam::PreintegratedAhrsMeasurements::equals | ( | const PreintegratedAhrsMeasurements & | other, |
double | tol = 1e-9 |
||
) | const |
equals
Definition at line 37 of file AHRSFactor.cpp.
void gtsam::PreintegratedAhrsMeasurements::integrateMeasurement | ( | const Vector3 & | measuredOmega, |
double | deltaT | ||
) |
Add a single Gyroscope measurement to the preintegration.
measureOmedga | Measured angular velocity (in body frame) |
deltaT | Time step |
Definition at line 50 of file AHRSFactor.cpp.
|
inline |
Definition at line 78 of file AHRSFactor.h.
Vector3 gtsam::PreintegratedAhrsMeasurements::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?
Definition at line 63 of file AHRSFactor.cpp.
|
inline |
Definition at line 80 of file AHRSFactor.h.
void gtsam::PreintegratedAhrsMeasurements::print | ( | const std::string & | s = "Preintegrated Measurements: " | ) | const |
Definition at line 30 of file AHRSFactor.cpp.
void gtsam::PreintegratedAhrsMeasurements::resetIntegration | ( | ) |
Reset inetgrated quantities to zero.
Definition at line 44 of file AHRSFactor.cpp.
|
inlineprivate |
Definition at line 121 of file AHRSFactor.h.
|
friend |
Definition at line 41 of file AHRSFactor.h.
|
friend |
Serialization function
Definition at line 119 of file AHRSFactor.h.
|
protected |
Angular rate bias values used during preintegration.
Definition at line 38 of file AHRSFactor.h.
|
protected |
Covariance matrix of the preintegrated measurements (first-order propagation from measurementCovariance)
Definition at line 39 of file AHRSFactor.h.