GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
Public Member Functions | Static Public Attributes | List of all members
gtsam::imuBias::ConstantBias Class Reference

Public Member Functions

Vector6 vector () const
 
const Vector3 & accelerometer () const
 
const Vector3 & gyroscope () const
 
Vector3 correctAccelerometer (const Vector3 &measurement, OptionalJacobian< 3, 6 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
 
Vector3 correctGyroscope (const Vector3 &measurement, OptionalJacobian< 3, 6 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
 
Standard Constructors
 ConstantBias ()
 
 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
 

Testable

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
 

Group

ConstantBias operator- () const
 
ConstantBias operator+ (const Vector6 &v) const
 
ConstantBias operator+ (const ConstantBias &b) const
 
ConstantBias operator- (const ConstantBias &b) const
 
static ConstantBias Identity ()
 

Member Function Documentation

◆ accelerometer()

const Vector3& gtsam::imuBias::ConstantBias::accelerometer ( ) const
inline

get accelerometer bias

◆ 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

equality up to tolerance

◆ gyroscope()

const Vector3& gtsam::imuBias::ConstantBias::gyroscope ( ) const
inline

get gyroscope bias

◆ 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]

ConstantBias gtsam::imuBias::ConstantBias::operator+ ( const ConstantBias b) const
inline

addition

◆ operator-() [1/2]

ConstantBias gtsam::imuBias::ConstantBias::operator- ( ) const
inline

inverse

◆ operator-() [2/2]

ConstantBias gtsam::imuBias::ConstantBias::operator- ( const ConstantBias b) const
inline

subtraction

◆ 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: