Go to the documentation of this file.
33 using Base = NoiseModelFactor2<NavState, NavState>;
36 using Base::evaluateError;
56 static const Vector3 b_accel{0.0, 0.0, 0.0};
57 static const Vector3 b_omega{0.0, 0.0, 0.0};
59 Matrix99 predicted_H_x1;
60 NavState predicted =
x1.update(b_accel, b_omega,
dt_, H1 ? &predicted_H_x1 :
nullptr, {}, {});
62 Matrix99 error_H_predicted;
66 *H1 = error_H_predicted * predicted_H_x1;
~ConstantVelocityFactor() override
double error(const Values &c) const override
Navigation state composing of attitude, position, and velocity.
noiseModel::Base::shared_ptr SharedNoiseModel
ConstantVelocityFactor(Key i, Key j, double dt, const SharedNoiseModel &model)
noiseModel::Diagonal::shared_ptr model
Non-linear factor base classes.
Matrix * OptionalMatrixType
Vector9 localCoordinates(const NavState &g, OptionalJacobian< 9, 9 > H1={}, OptionalJacobian< 9, 9 > H2={}) const
localCoordinates with optional derivatives
std::uint64_t Key
Integer nonlinear key type.
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
gtsam::Vector evaluateError(const NavState &x1, const NavState &x2, OptionalMatrixType H1, OptionalMatrixType H2) const override
Caclulate error: (x2 - x1.update(dt))) where X1 and X1 are NavStates and dt is the time difference in...
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:02:02