gtsam
4.0.0
gtsam
|
PreintegratedRotation is the base class for all PreintegratedMeasurements classes (in AHRSFactor, ImuFactor, and CombinedImuFactor).
It includes the definitions of the preintegrated rotation.
Public Member Functions | |
Constructors | |
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. | |
Basic utilities | |
void | resetIntegration () |
Re-initialize PreintegratedMeasurements. | |
bool | matchesParamsWith (const PreintegratedRotation &other) const |
check parameters equality: checks whether shared pointer points to same Params object. | |
Access instance variables | |
const boost::shared_ptr< Params > & | params () const |
const double & | deltaTij () const |
const Rot3 & | deltaRij () const |
const Matrix3 & | delRdelBiasOmega () const |
Testable | |
void | print (const std::string &s) const |
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 |
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. | |
Public Types | |
typedef PreintegratedRotationParams | Params |
Protected Member Functions | |
PreintegratedRotation () | |
Default constructor for serialization. | |
Protected Attributes | |
boost::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 | boost::serialization::access |
Serialization function. | |
Rot3 gtsam::PreintegratedRotation::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 gtsam::PreintegratedRotation::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_.