#include <ImuBias.h>
Definition at line 30 of file ImuBias.h.
gtsam::imuBias::ConstantBias::ConstantBias |
( |
| ) |
|
|
inline |
gtsam::imuBias::ConstantBias::ConstantBias |
( |
const Vector3 & |
biasAcc, |
|
|
const Vector3 & |
biasGyro |
|
) |
| |
|
inline |
gtsam::imuBias::ConstantBias::ConstantBias |
( |
const Vector6 & |
v | ) |
|
|
inlineexplicit |
const Vector3& gtsam::imuBias::ConstantBias::accelerometer |
( |
| ) |
const |
|
inline |
get accelerometer bias
Definition at line 59 of file ImuBias.h.
Correct an accelerometer measurement using this bias model, and optionally compute Jacobians
Definition at line 69 of file ImuBias.h.
Correct a gyroscope measurement using this bias model, and optionally compute Jacobians
Definition at line 78 of file ImuBias.h.
bool gtsam::imuBias::ConstantBias::equals |
( |
const ConstantBias & |
expected, |
|
|
double |
tol = 1e-5 |
|
) |
| const |
|
inline |
equality up to tolerance
Definition at line 98 of file ImuBias.h.
static ConstantBias gtsam::imuBias::ConstantBias::Expmap |
( |
const Vector6 & |
v | ) |
|
|
inlinestatic |
const Vector3& gtsam::imuBias::ConstantBias::gyroscope |
( |
| ) |
const |
|
inline |
get gyroscope bias
Definition at line 64 of file ImuBias.h.
static ConstantBias gtsam::imuBias::ConstantBias::identity |
( |
| ) |
|
|
inlinestatic |
identity for group operation
Definition at line 108 of file ImuBias.h.
Vector6 gtsam::imuBias::ConstantBias::localCoordinates |
( |
const ConstantBias & |
q | ) |
|
|
inline |
static Vector6 gtsam::imuBias::ConstantBias::Logmap |
( |
const ConstantBias & |
p | ) |
|
|
inlinestatic |
ConstantBias gtsam::imuBias::ConstantBias::operator+ |
( |
const Vector6 & |
v | ) |
const |
|
inline |
addition of vector on right
Definition at line 118 of file ImuBias.h.
ConstantBias gtsam::imuBias::ConstantBias::operator- |
( |
| ) |
const |
|
inline |
void gtsam::imuBias::ConstantBias::print |
( |
const std::string & |
s = "" | ) |
const |
print with optional string
Definition at line 75 of file ImuBias.cpp.
ConstantBias gtsam::imuBias::ConstantBias::retract |
( |
const Vector6 & |
v | ) |
|
|
inline |
template<class ARCHIVE >
void gtsam::imuBias::ConstantBias::serialize |
( |
ARCHIVE & |
ar, |
|
|
const unsigned |
int |
|
) |
| |
|
inlineprivate |
Vector6 gtsam::imuBias::ConstantBias::vector |
( |
| ) |
const |
|
inline |
return the accelerometer and gyro biases in a single vector
Definition at line 52 of file ImuBias.h.
friend class boost::serialization::access |
|
friend |
Serialization function
Definition at line 165 of file ImuBias.h.
GTSAM_EXPORT friend std::ostream& operator<< |
( |
std::ostream & |
os, |
|
|
const ConstantBias & |
bias |
|
) |
| |
|
friend |
Vector3 gtsam::imuBias::ConstantBias::biasAcc_ |
|
private |
The units for stddev are σ = m/s² or m √Hz/s²
Definition at line 32 of file ImuBias.h.
Vector3 gtsam::imuBias::ConstantBias::biasGyro_ |
|
private |
The units for stddev are σ = rad/s or rad √Hz/s.
Definition at line 33 of file ImuBias.h.
const size_t gtsam::imuBias::ConstantBias::dimension = 6 |
|
static |
dimension of the variable - used to autodetect sizes
Definition at line 37 of file ImuBias.h.
The documentation for this class was generated from the following files: