#include <ImuBias.h>
Definition at line 32 of file ImuBias.h.
◆ ConstantBias() [1/3]
gtsam::imuBias::ConstantBias::ConstantBias |
( |
| ) |
|
|
inline |
◆ ConstantBias() [2/3]
gtsam::imuBias::ConstantBias::ConstantBias |
( |
const Vector3 & |
biasAcc, |
|
|
const Vector3 & |
biasGyro |
|
) |
| |
|
inline |
◆ ConstantBias() [3/3]
gtsam::imuBias::ConstantBias::ConstantBias |
( |
const Vector6 & |
v | ) |
|
|
inlineexplicit |
◆ accelerometer()
const Vector3& gtsam::imuBias::ConstantBias::accelerometer |
( |
| ) |
const |
|
inline |
get accelerometer bias
Definition at line 66 of file ImuBias.h.
◆ correctAccelerometer()
Correct an accelerometer measurement using this bias model, and optionally compute Jacobians
Definition at line 76 of file ImuBias.h.
◆ correctGyroscope()
Correct a gyroscope measurement using this bias model, and optionally compute Jacobians
Definition at line 85 of file ImuBias.h.
◆ equals()
bool gtsam::imuBias::ConstantBias::equals |
( |
const ConstantBias & |
expected, |
|
|
double |
tol = 1e-5 |
|
) |
| const |
|
inline |
equality up to tolerance
Definition at line 104 of file ImuBias.h.
◆ gyroscope()
const Vector3& gtsam::imuBias::ConstantBias::gyroscope |
( |
| ) |
const |
|
inline |
get gyroscope bias
Definition at line 71 of file ImuBias.h.
◆ Identity()
static ConstantBias gtsam::imuBias::ConstantBias::Identity |
( |
| ) |
|
|
inlinestatic |
identity for group operation
Definition at line 114 of file ImuBias.h.
◆ operator+() [1/2]
◆ operator+() [2/2]
ConstantBias gtsam::imuBias::ConstantBias::operator+ |
( |
const Vector6 & |
v | ) |
const |
|
inline |
addition of vector on right
Definition at line 124 of file ImuBias.h.
◆ operator-() [1/2]
ConstantBias gtsam::imuBias::ConstantBias::operator- |
( |
| ) |
const |
|
inline |
◆ operator-() [2/2]
◆ print()
void gtsam::imuBias::ConstantBias::print |
( |
const std::string & |
s = "" | ) |
const |
print with optional string
Definition at line 75 of file ImuBias.cpp.
◆ vector()
Vector6 gtsam::imuBias::ConstantBias::vector |
( |
| ) |
const |
|
inline |
return the accelerometer and gyro biases in a single vector
Definition at line 59 of file ImuBias.h.
◆ operator<<
GTSAM_EXPORT friend std::ostream& operator<< |
( |
std::ostream & |
os, |
|
|
const ConstantBias & |
bias |
|
) |
| |
|
friend |
◆ biasAcc_
Vector3 gtsam::imuBias::ConstantBias::biasAcc_ |
|
private |
The units for stddev are σ = m/s² or m √Hz/s²
Definition at line 34 of file ImuBias.h.
◆ biasGyro_
Vector3 gtsam::imuBias::ConstantBias::biasGyro_ |
|
private |
The units for stddev are σ = rad/s or rad √Hz/s.
Definition at line 35 of file ImuBias.h.
◆ dimension
const size_t gtsam::imuBias::ConstantBias::dimension = 6 |
|
static |
dimension of the variable - used to autodetect sizes
Definition at line 39 of file ImuBias.h.
The documentation for this class was generated from the following files: