Go to the documentation of this file.
14 const std::list<Vector>&
F,
const double g_e,
bool flat) {
24 const Matrix&
F,
const double g_e,
bool flat) {
35 b_g = (
Vector3(3) << 0.0, 0.0, meanF.norm()).finished();
45 b_g = -
g_e * meanF/meanF.norm();
82 const double dt)
const {
85 #ifndef MODEL_NAV_FRAME_ROTATION
91 Vector3 b_omega_in; b_omega_in.setZero();
94 Vector3 b_omega_bn = b_omega_in - b_omega_ib;
Vector3 x_g_
gyroscope bias
static Mechanization_bRn2 initializeVector(const std::list< Vector > &U, const std::list< Vector > &F, const double g_e=0, bool flat=false)
Pose3 g1(Rot3(), Point3(100.0, 0.0, 300.0))
Class compose(const Class &g) const
Vector3 x_a_
accelerometer bias
Mechanization_bRn2 integrate(const Vector3 &u, const double dt) const
Mechanization_bRn2 correct(const Vector9 &dx) const
static Rot3 Ypr(double y, double p, double r, OptionalJacobian< 3, 1 > Hy={}, OptionalJacobian< 3, 1 > Hp={}, OptionalJacobian< 3, 1 > Hr={})
Rot3 bRn_
rotation from nav to body
Vector concatVectors(const std::list< Vector > &vs)
Vector3 b_g(double g_e) const
gravity in the body frame
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
static Rot3 Rodrigues(const Vector3 &w)
Pose3 g2(g1.expmap(h *V1_g1))
Rot3 inverse() const
inverse of a rotation
AnnoyingScalar atan2(const AnnoyingScalar &y, const AnnoyingScalar &x)
Mechanization_bRn2(const Rot3 &initial_bRn=Rot3(), const Vector3 &initial_x_g=Z_3x1, const Vector3 &initial_x_a=Z_3x1)
const Vector3 & x_a() const
const Vector3 & x_g() const
Jet< T, N > sqrt(const Jet< T, N > &f)
static Mechanization_bRn2 initialize(const Matrix &U, const Matrix &F, const double g_e=0, bool flat=false)
Matrix version of initialize.
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:03:10