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.
|
| PreintegratedAhrsMeasurements () |
| Default constructor, only for serialization and wrappers.
|
|
| PreintegratedAhrsMeasurements (const boost::shared_ptr< Params > &p, const Vector3 &biasHat) |
| Default constructor, initialize with no measurements. More...
|
|
| PreintegratedAhrsMeasurements (const boost::shared_ptr< Params > &p, const Vector3 &bias_hat, double deltaTij, const Rot3 &deltaRij, const Matrix3 &delRdelBiasOmega, const Matrix3 &preint_meas_cov) |
| Non-Default constructor, initialize with measurements. More...
|
|
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) |
| 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) |
|
| 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 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 |
| 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 | 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_.
|
|
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.
|
|