Go to the documentation of this file.
   33 PreintegrationBase::PreintegrationBase(
const std::shared_ptr<Params>& 
p,
 
   35     : p_(
p), biasHat_(biasHat), deltaTij_(0.0) {
 
   41   os << 
"    deltaRij.ypr = (" << pim.
deltaRij().
ypr().transpose() << 
")" << endl;
 
   42   os << 
"    deltaPij = " << pim.
deltaPij().transpose() << endl;
 
   43   os << 
"    deltaVij = " << pim.
deltaVij().transpose() << endl;
 
   51   cout << (
s.empty() ? 
s : 
s + 
"\n") << *
this << endl;
 
   77   const Vector3 correctedOmega = bRs * unbiasedOmega;
 
   80   if (correctedAcc_H_unbiasedAcc) *correctedAcc_H_unbiasedAcc = bRs;
 
   81   if (correctedAcc_H_unbiasedOmega) *correctedAcc_H_unbiasedOmega = Z_3x3;
 
   82   if (correctedOmega_H_unbiasedOmega) *correctedOmega_H_unbiasedOmega = bRs;
 
   86   if (!b_arm.isZero()) {
 
   89     const Matrix3 body_Omega_body = 
skewSymmetric(correctedOmega);
 
   90     const Vector3 b_velocity_bs = body_Omega_body * b_arm; 
 
   94     if (correctedAcc_H_unbiasedOmega) {
 
   95       double wdp = correctedOmega.dot(b_arm);
 
   96       const Matrix3 diag_wdp = Vector3::Constant(wdp).asDiagonal();
 
   97       *correctedAcc_H_unbiasedOmega = -( diag_wdp
 
   98           + correctedOmega * b_arm.transpose()) * bRs.matrix()
 
   99           + 2 * b_arm * unbiasedOmega.transpose();
 
  120   Matrix96 D_biasCorrected_bias;
 
  122                                              H2 ? &D_biasCorrected_bias : 
nullptr);
 
  125   Matrix9 D_delta_state, D_delta_biasCorrected;
 
  127                                   p().omegaCoriolis, 
p().use2ndOrderCoriolis, H1 ? &D_delta_state : 
nullptr,
 
  128                                   H2 ? &D_delta_biasCorrected : 
nullptr);
 
  131   Matrix9 D_predict_state, D_predict_delta;
 
  133                                      H1 ? &D_predict_state : 
nullptr,
 
  134                                      H1 || H2 ? &D_predict_delta : 
nullptr);
 
  136     *H1 = D_predict_state + D_predict_delta * D_delta_state;
 
  138     *H2 = D_predict_delta * D_delta_biasCorrected * D_biasCorrected_bias;
 
  151   Matrix96 D_predict_bias_i;
 
  153       state_i, bias_i, H1 ? &D_predict_state_i : 0, H3 ? &D_predict_bias_i : 0);
 
  156   Matrix9 D_error_state_j, D_error_predict;
 
  159                                H1 || H3 ? &D_error_predict : 0);
 
  161   if (H1) *H1 << D_error_predict * D_predict_state_i;
 
  162   if (H2) *H2 << D_error_state_j;
 
  163   if (H3) *H3 << D_error_predict * D_predict_bias_i;
 
  181   Matrix9 D_error_state_i, D_error_state_j;
 
  183                          H1 || H2 ? &D_error_state_i : 0, H3 || H4 ? &D_error_state_j : 0, H5);
 
  190   if (H1) *H1 << D_error_state_i.leftCols<6>();
 
  191   if (H2) *H2 << D_error_state_i.rightCols<3>() * state_i.
R().transpose();
 
  192   if (H3) *H3 << D_error_state_j.leftCols<6>();
 
  193   if (H4) *H4 << D_error_state_j.rightCols<3>() * state_j.
R().transpose();
 
  
virtual void integrateMeasurement(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt)
Version without derivatives.
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={}, OptionalJacobian< 9, 3 > H2={}, OptionalJacobian< 9, 6 > H3={}, OptionalJacobian< 9, 3 > H4={}, OptionalJacobian< 9, 6 > H5={}) const
const Vector3 & gyroscope() const
Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
virtual void update(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt, Matrix9 *A, Matrix93 *B, Matrix93 *C)=0
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
virtual void print(const std::string &s="") const
std::pair< Vector3, Vector3 > correctMeasurementsBySensorPose(const Vector3 &unbiasedAcc, const Vector3 &unbiasedOmega, OptionalJacobian< 3, 3 > correctedAcc_H_unbiasedAcc={}, OptionalJacobian< 3, 3 > correctedAcc_H_unbiasedOmega={}, OptionalJacobian< 3, 3 > correctedOmega_H_unbiasedOmega={}) const
ofstream os("timeSchurFactors.csv")
static Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0))
Matrix3 skewSymmetric(double wx, double wy, double wz)
Bias biasHat_
Acceleration and gyro bias used for preintegration.
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
Vector9 correctPIM(const Vector9 &pim, double dt, const Vector3 &n_gravity, const std::optional< Vector3 > &omegaCoriolis, bool use2ndOrderCoriolis=false, OptionalJacobian< 9, 9 > H1={}, OptionalJacobian< 9, 9 > H2={}) const
Vector3 ypr(OptionalJacobian< 3, 3 > H={}) const
Some functions to compute numerical derivatives.
const Vector3 measuredOmega
virtual Vector3 deltaPij() const =0
const Vector3 & accelerometer() const
virtual void resetIntegration()=0
NavState predict(const NavState &state_i, const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 9 > H1={}, OptionalJacobian< 9, 6 > H2={}) const
Predict state at time j.
Params & p() const
const reference to params
Matrix3 R() const
Return rotation matrix. Induces computation in quaternion mode.
std::optional< Pose3 > body_P_sensor
The pose of the sensor in the body frame.
virtual Vector3 deltaVij() const =0
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.
Matrix< Scalar, Dynamic, Dynamic > C
virtual Rot3 deltaRij() const =0
double deltaTij_
Time interval from i to j.
virtual Vector9 biasCorrectedDelta(const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 6 > H={}) const =0
NavState retract(const Vector9 &v, OptionalJacobian< 9, 9 > H1={}, OptionalJacobian< 9, 9 > H2={}) const
retract with optional derivatives
const imuBias::ConstantBias & biasHat() const
static const Vector3 measuredAcc
void resetIntegrationAndSetBias(const Bias &biasHat)
Vector3 correctedAcc(const PreintegratedImuMeasurements &pim, const Vector3 &measuredAcc, const Vector3 &measuredOmega)
Vector9 localCoordinates(const NavState &g, OptionalJacobian< 9, 9 > H1={}, OptionalJacobian< 9, 9 > H2={}) const
localCoordinates with optional derivatives
gtsam
Author(s): 
autogenerated on Wed May 28 2025 03:02:36