PreintegrationBase is the base class for PreintegratedMeasurements (in ImuFactor) and CombinedPreintegratedMeasurements (in CombinedImuFactor).
It includes the definitions of the preintegrated variables and the methods to access, print, and compare them.
|
class | boost::serialization::access |
| Serialization function.
|
|
std::pair< Vector3, Vector3 > | correctMeasurementsBySensorPose (const Vector3 &unbiasedAcc, const Vector3 &unbiasedOmega, OptionalJacobian< 3, 3 > correctedAcc_H_unbiasedAcc=boost::none, OptionalJacobian< 3, 3 > correctedAcc_H_unbiasedOmega=boost::none, OptionalJacobian< 3, 3 > correctedOmega_H_unbiasedOmega=boost::none) const |
| Subtract estimate and correct for sensor pose Compute the derivatives due to non-identity body_P_sensor (rotation and centrifugal acc) Ignore D_correctedOmega_measuredAcc as it is trivially zero.
|
|
virtual void | update (const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt, Matrix9 *A, Matrix93 *B, Matrix93 *C)=0 |
| Update preintegrated measurements and get derivatives It takes measured quantities in the j frame Modifies preintegrated quantities in place after correcting for bias and possibly sensor pose. More...
|
|
virtual void | integrateMeasurement (const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt) |
| Version without derivatives. More...
|
|
virtual Vector9 | biasCorrectedDelta (const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 6 > H=boost::none) const =0 |
| Given the estimate of the bias, return a NavState tangent vector summarizing the preintegrated IMU measurements so far. More...
|
|
NavState | predict (const NavState &state_i, const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 9 > H1=boost::none, OptionalJacobian< 9, 6 > H2=boost::none) const |
| Predict state at time j.
|
|
Vector9 | computeError (const NavState &state_i, const NavState &state_j, const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 9 > H1, OptionalJacobian< 9, 9 > H2, OptionalJacobian< 9, 6 > H3) const |
| Calculate error given navStates.
|
|
Vector9 | computeErrorAndJacobians (const Pose3 &pose_i, const Vector3 &vel_i, const Pose3 &pose_j, const Vector3 &vel_j, const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 6 > H1=boost::none, OptionalJacobian< 9, 3 > H2=boost::none, OptionalJacobian< 9, 6 > H3=boost::none, OptionalJacobian< 9, 3 > H4=boost::none, OptionalJacobian< 9, 6 > H5=boost::none) const |
| Compute errors w.r.t. More...
|
|
|
|
| PreintegrationBase (const boost::shared_ptr< Params > &p, const imuBias::ConstantBias &biasHat=imuBias::ConstantBias()) |
| Constructor, initializes the variables in the base class. More...
|
|
|
Re-initialize PreintegratedMeasurements and set new bias
|
virtual void | resetIntegration ()=0 |
|
void | resetIntegrationAndSetBias (const Bias &biasHat) |
|
bool | matchesParamsWith (const PreintegrationBase &other) const |
| check parameters equality: checks whether shared pointer points to same Params object.
|
|
const boost::shared_ptr< Params > & | params () const |
| shared pointer to params
|
|
Params & | p () const |
| const reference to params
|
|
|
const imuBias::ConstantBias & | biasHat () const |
|
double | deltaTij () const |
|
virtual Vector3 | deltaPij () const =0 |
|
virtual Vector3 | deltaVij () const =0 |
|
virtual Rot3 | deltaRij () const =0 |
|
virtual NavState | deltaXij () const =0 |
|
Vector6 | biasHatVector () const |
|