#include <PreintegratedRotation.h>
Public Types | |
typedef PreintegratedRotationParams | Params |
Public Member Functions | |
Constructors | |
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... | |
Basic utilities | |
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... | |
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 |
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... | |
Protected Member Functions | |
PreintegratedRotation () | |
Default constructor for serialization. More... | |
Protected Attributes | |
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 | boost::serialization::access |
PreintegratedRotation is the base class for all PreintegratedMeasurements classes (in AHRSFactor, ImuFactor, and CombinedImuFactor). It includes the definitions of the preintegrated rotation.
Definition at line 89 of file PreintegratedRotation.h.
Definition at line 91 of file PreintegratedRotation.h.
|
inlineprotected |
Default constructor for serialization.
Definition at line 102 of file PreintegratedRotation.h.
|
inlineexplicit |
Default constructor, resets integration to zero.
Definition at line 109 of file PreintegratedRotation.h.
|
inline |
Explicit initialization of all class members.
Definition at line 114 of file PreintegratedRotation.h.
Rot3 gtsam::PreintegratedRotation::biascorrectedDeltaRij | ( | const Vector3 & | biasOmegaIncr, |
OptionalJacobian< 3, 3 > | H = boost::none |
||
) | const |
Return a bias corrected version of the integrated rotation, with optional Jacobian.
Definition at line 115 of file PreintegratedRotation.cpp.
|
inline |
Definition at line 144 of file PreintegratedRotation.h.
|
inline |
Definition at line 141 of file PreintegratedRotation.h.
|
inline |
Definition at line 138 of file PreintegratedRotation.h.
bool gtsam::PreintegratedRotation::equals | ( | const PreintegratedRotation & | other, |
double | tol | ||
) | const |
Definition at line 63 of file PreintegratedRotation.cpp.
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.
Definition at line 71 of file PreintegratedRotation.cpp.
Integrate coriolis correction in body frame rot_i.
Definition at line 125 of file PreintegratedRotation.cpp.
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_.
Definition at line 92 of file PreintegratedRotation.cpp.
|
inline |
check parameters equality: checks whether shared pointer points to same Params object.
Definition at line 128 of file PreintegratedRotation.h.
|
inline |
Definition at line 135 of file PreintegratedRotation.h.
void gtsam::PreintegratedRotation::print | ( | const std::string & | s | ) | const |
Definition at line 57 of file PreintegratedRotation.cpp.
void gtsam::PreintegratedRotation::resetIntegration | ( | ) |
Re-initialize PreintegratedMeasurements.
Definition at line 51 of file PreintegratedRotation.cpp.
|
inlineprivate |
Definition at line 183 of file PreintegratedRotation.h.
|
friend |
Serialization function
Definition at line 181 of file PreintegratedRotation.h.
|
protected |
Jacobian of preintegrated rotation w.r.t. angular rate bias.
Definition at line 99 of file PreintegratedRotation.h.
|
protected |
Preintegrated relative orientation (in frame i)
Definition at line 98 of file PreintegratedRotation.h.
|
protected |
Time interval from i to j.
Definition at line 97 of file PreintegratedRotation.h.
|
protected |
Parameters.
Definition at line 95 of file PreintegratedRotation.h.