|
static Mechanization_bRn2 | initializeVector (const std::list< Vector > &U, const std::list< Vector > &F, const double g_e=0, bool flat=false) |
| Initialize the first Mechanization state. More...
|
|
static Mechanization_bRn2 | initialize (const Matrix &U, const Matrix &F, const double g_e=0, bool flat=false) |
| Matrix version of initialize.
|
|
◆ Mechanization_bRn2()
gtsam::Mechanization_bRn2::Mechanization_bRn2 |
( |
const Rot3 & |
initial_bRn = Rot3() , |
|
|
const Vector3 & |
initial_x_g = Z_3x1 , |
|
|
const Vector3 & |
initial_x_a = Z_3x1 |
|
) |
| |
|
inline |
Constructor.
- Parameters
-
initial_bRn | initial rotation from nav to body frame |
initial_x_g | initial gyro bias |
r3 | Z-axis of rotated frame |
◆ correct()
Correct AHRS full state given error state dx.
- Parameters
-
obj | The current state |
dx | The error used to correct and return a new state |
◆ initializeVector()
Mechanization_bRn2 gtsam::Mechanization_bRn2::initializeVector |
( |
const std::list< Vector > & |
U, |
|
|
const std::list< Vector > & |
F, |
|
|
const double |
g_e = 0 , |
|
|
bool |
flat = false |
|
) |
| |
|
static |
Initialize the first Mechanization state.
- Parameters
-
U | a list of gyro measurement vectors |
F | a list of accelerometer measurement vectors |
g_e | gravity magnitude |
flat | flag saying whether this is a flat trim init |
◆ integrate()
Mechanization_bRn2 gtsam::Mechanization_bRn2::integrate |
( |
const Vector3 & |
u, |
|
|
const double |
dt |
|
) |
| const |
Integrate to get new state.
- Parameters
-
obj | The current state |
u | gyro measurement to integrate |
dt | time elapsed since previous state in seconds |
The documentation for this class was generated from the following files:
- /Users/dellaert/git/github/gtsam_unstable/slam/Mechanization_bRn2.h
- /Users/dellaert/git/github/gtsam_unstable/slam/Mechanization_bRn2.cpp