gtsam 4.2
gtsam
Loading...
Searching...
No Matches
gtsam::imuBias::ConstantBias Class Reference

Advanced Interface

class boost::serialization::access
 Serialization function.

Testable

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

Group

ConstantBias operator- () const
 inverse
ConstantBias operator+ (const Vector6 &v) const
 addition of vector on right
ConstantBias operator+ (const ConstantBias &b) const
 addition
ConstantBias operator- (const ConstantBias &b) const
 subtraction
static ConstantBias Identity ()
 identity for group operation

Public Member Functions

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.
Standard Constructors
 ConstantBias (const Vector3 &biasAcc, const Vector3 &biasGyro)
 ConstantBias (const Vector6 &v)

Static Public Attributes

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:
  • /tmp/gtsam-4.2-docs.H5EUbA/src/gtsam/navigation/ImuBias.h
  • /tmp/gtsam-4.2-docs.H5EUbA/src/gtsam/navigation/ImuBias.cpp