#include <Mechanization_bRn2.h>
Definition at line 17 of file Mechanization_bRn2.h.
◆ Mechanization_bRn2() [1/2]
Constructor
- Parameters
-
initial_bRn | initial rotation from nav to body frame |
initial_x_g | initial gyro bias |
r3 | Z-axis of rotated frame |
Definition at line 32 of file Mechanization_bRn2.h.
◆ Mechanization_bRn2() [2/2]
◆ b_g()
Vector3 gtsam::Mechanization_bRn2::b_g |
( |
double |
g_e | ) |
const |
|
inline |
◆ bRn()
const Rot3& gtsam::Mechanization_bRn2::bRn |
( |
| ) |
const |
|
inline |
◆ 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 |
Definition at line 68 of file Mechanization_bRn2.cpp.
◆ initialize()
◆ 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 |
Definition at line 13 of file Mechanization_bRn2.cpp.
◆ integrate()
Integrate to get new state
- Parameters
-
obj | The current state |
u | gyro measurement to integrate |
dt | time elapsed since previous state in seconds |
Definition at line 81 of file Mechanization_bRn2.cpp.
◆ print()
void gtsam::Mechanization_bRn2::print |
( |
const std::string & |
s = "" | ) |
const |
|
inline |
◆ x_a()
const Vector3& gtsam::Mechanization_bRn2::x_a |
( |
| ) |
const |
|
inline |
◆ x_g()
const Vector3& gtsam::Mechanization_bRn2::x_g |
( |
| ) |
const |
|
inline |
◆ bRn_
Rot3 gtsam::Mechanization_bRn2::bRn_ |
|
private |
◆ x_a_
Vector3 gtsam::Mechanization_bRn2::x_a_ |
|
private |
◆ x_g_
Vector3 gtsam::Mechanization_bRn2::x_g_ |
|
private |
The documentation for this class was generated from the following files: