|
class | boost::serialization::access |
| Serialization function.
|
|
|
GTSAM_EXPORT friend std::ostream & | operator<< (std::ostream &os, const ConstantBias &bias) |
| ostream operator
|
|
void | print (const std::string &s="") const |
| print with optional string
|
|
bool | equals (const ConstantBias &expected, double tol=1e-5) const |
| equality up to tolerance
|
|
|
| ConstantBias (const Vector3 &biasAcc, const Vector3 &biasGyro) |
|
| ConstantBias (const Vector6 &v) |
|
Vector6 | vector () const |
| return the accelerometer and gyro biases in a single vector
|
|
const Vector3 & | accelerometer () const |
| get accelerometer bias
|
|
const Vector3 & | gyroscope () const |
| get gyroscope bias
|
|
Vector3 | correctAccelerometer (const Vector3 &measurement, OptionalJacobian< 3, 6 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const |
| Correct an accelerometer measurement using this bias model, and optionally compute Jacobians.
|
|
Vector3 | correctGyroscope (const Vector3 &measurement, OptionalJacobian< 3, 6 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const |
| Correct a gyroscope measurement using this bias model, and optionally compute Jacobians.
|
|
|
static const size_t | dimension = 6 |
| dimension of the variable - used to autodetect sizes
|
|
The documentation for this class was generated from the following files:
- /Users/dellaert/git/github/gtsam/navigation/ImuBias.h
- /Users/dellaert/git/github/gtsam/navigation/ImuBias.cpp