|
|
static const size_t | dimension = 6 |
| | dimension of the variable - used to autodetect sizes
|
| |
|
|
void | print (const std::string &s="") const |
| | print with optional string
|
| |
| bool | equals (const ConstantBias &expected, double tol=1e-5) const |
| |
|
GTSAM_EXPORT friend std::ostream & | operator<< (std::ostream &os, const ConstantBias &bias) |
| | ostream operator
|
| |
◆ accelerometer()
| const Vector3& gtsam::imuBias::ConstantBias::accelerometer |
( |
| ) |
const |
|
inline |
◆ correctAccelerometer()
| Vector3 gtsam::imuBias::ConstantBias::correctAccelerometer |
( |
const Vector3 & |
measurement, |
|
|
OptionalJacobian< 3, 6 > |
H1 = {}, |
|
|
OptionalJacobian< 3, 3 > |
H2 = {} |
|
) |
| const |
|
inline |
Correct an accelerometer measurement using this bias model, and optionally compute Jacobians
◆ correctGyroscope()
| Vector3 gtsam::imuBias::ConstantBias::correctGyroscope |
( |
const Vector3 & |
measurement, |
|
|
OptionalJacobian< 3, 6 > |
H1 = {}, |
|
|
OptionalJacobian< 3, 3 > |
H2 = {} |
|
) |
| const |
|
inline |
Correct a gyroscope measurement using this bias model, and optionally compute Jacobians
◆ equals()
| bool gtsam::imuBias::ConstantBias::equals |
( |
const ConstantBias & |
expected, |
|
|
double |
tol = 1e-5 |
|
) |
| const |
|
inline |
◆ gyroscope()
| const Vector3& gtsam::imuBias::ConstantBias::gyroscope |
( |
| ) |
const |
|
inline |
◆ Identity()
| static ConstantBias gtsam::imuBias::ConstantBias::Identity |
( |
| ) |
|
|
inlinestatic |
identity for group operation
◆ operator+() [1/2]
| ConstantBias gtsam::imuBias::ConstantBias::operator+ |
( |
const Vector6 & |
v | ) |
const |
|
inline |
addition of vector on right
◆ operator+() [2/2]
◆ operator-() [1/2]
| ConstantBias gtsam::imuBias::ConstantBias::operator- |
( |
| ) |
const |
|
inline |
◆ operator-() [2/2]
◆ vector()
| Vector6 gtsam::imuBias::ConstantBias::vector |
( |
| ) |
const |
|
inline |
return the accelerometer and gyro biases in a single vector
The documentation for this class was generated from the following file:
- /home/docs/checkouts/readthedocs.org/user_builds/gtsam-jlblanco-docs/checkouts/latest/gtsam/navigation/ImuBias.h