Public Member Functions | Static Public Attributes | Private Attributes | List of all members
gtsam::imuBias::ConstantBias Class Reference

#include <ImuBias.h>

Public Member Functions

const Vector3accelerometer () const
 
 ConstantBias ()
 
 ConstantBias (const Vector3 &biasAcc, const Vector3 &biasGyro)
 
 ConstantBias (const Vector6 &v)
 
Vector3 correctAccelerometer (const Vector3 &measurement, OptionalJacobian< 3, 6 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
 
Vector3 correctGyroscope (const Vector3 &measurement, OptionalJacobian< 3, 6 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
 
const Vector3gyroscope () const
 
Vector6 vector () const
 

Static Public Attributes

static const size_t dimension = 6
 dimension of the variable - used to autodetect sizes More...
 

Private Attributes

Vector3 biasAcc_
 The units for stddev are σ = m/s² or m √Hz/s² More...
 
Vector3 biasGyro_
 The units for stddev are σ = rad/s or rad √Hz/s. More...
 

Testable

GTSAM_EXPORT friend std::ostream & operator<< (std::ostream &os, const ConstantBias &bias)
 ostream operator More...
 
void print (const std::string &s="") const
 print with optional string More...
 
bool equals (const ConstantBias &expected, double tol=1e-5) const
 

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 ()
 

Deprecated

ConstantBias inverse ()
 
ConstantBias compose (const ConstantBias &q)
 
ConstantBias between (const ConstantBias &q)
 
Vector6 localCoordinates (const ConstantBias &q)
 
ConstantBias retract (const Vector6 &v)
 
static Vector6 Logmap (const ConstantBias &p)
 
static ConstantBias Expmap (const Vector6 &v)
 

Advanced Interface

class boost::serialization::access
 
template<class ARCHIVE >
void serialize (ARCHIVE &ar, const unsigned int)
 

Detailed Description

Definition at line 30 of file ImuBias.h.

Constructor & Destructor Documentation

gtsam::imuBias::ConstantBias::ConstantBias ( )
inline

Definition at line 39 of file ImuBias.h.

gtsam::imuBias::ConstantBias::ConstantBias ( const Vector3 biasAcc,
const Vector3 biasGyro 
)
inline

Definition at line 43 of file ImuBias.h.

gtsam::imuBias::ConstantBias::ConstantBias ( const Vector6 &  v)
inlineexplicit

Definition at line 47 of file ImuBias.h.

Member Function Documentation

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

get accelerometer bias

Definition at line 59 of file ImuBias.h.

ConstantBias gtsam::imuBias::ConstantBias::between ( const ConstantBias q)
inline

Definition at line 142 of file ImuBias.h.

ConstantBias gtsam::imuBias::ConstantBias::compose ( const ConstantBias q)
inline

Definition at line 139 of file ImuBias.h.

Vector3 gtsam::imuBias::ConstantBias::correctAccelerometer ( const Vector3 measurement,
OptionalJacobian< 3, 6 >  H1 = boost::none,
OptionalJacobian< 3, 3 >  H2 = boost::none 
) const
inline

Correct an accelerometer measurement using this bias model, and optionally compute Jacobians

Definition at line 69 of file ImuBias.h.

Vector3 gtsam::imuBias::ConstantBias::correctGyroscope ( const Vector3 measurement,
OptionalJacobian< 3, 6 >  H1 = boost::none,
OptionalJacobian< 3, 3 >  H2 = boost::none 
) const
inline

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

Definition at line 154 of file ImuBias.h.

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.

ConstantBias gtsam::imuBias::ConstantBias::inverse ( )
inline

Definition at line 136 of file ImuBias.h.

Vector6 gtsam::imuBias::ConstantBias::localCoordinates ( const ConstantBias q)
inline

Definition at line 145 of file ImuBias.h.

static Vector6 gtsam::imuBias::ConstantBias::Logmap ( const ConstantBias p)
inlinestatic

Definition at line 151 of file ImuBias.h.

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 ConstantBias b) const
inline

addition

Definition at line 123 of file ImuBias.h.

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

inverse

Definition at line 113 of file ImuBias.h.

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

subtraction

Definition at line 128 of file ImuBias.h.

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

Definition at line 148 of file ImuBias.h.

template<class ARCHIVE >
void gtsam::imuBias::ConstantBias::serialize ( ARCHIVE &  ar,
const unsigned  int 
)
inlineprivate

Definition at line 167 of file ImuBias.h.

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.

Friends And Related Function Documentation

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

ostream operator

Definition at line 68 of file ImuBias.cpp.

Member Data Documentation

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:


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:58:37