#include <IMUFactor.h>
Public Types | |
typedef NoiseModelFactor2< POSE, POSE > | Base |
typedef IMUFactor< POSE > | This |
Public Types inherited from gtsam::NoiseModelFactor2< POSE, POSE > | |
typedef POSE | X1 |
typedef POSE | X2 |
Public Types inherited from gtsam::NoiseModelFactor | |
typedef boost::shared_ptr< This > | shared_ptr |
Public Types inherited from gtsam::NonlinearFactor | |
typedef boost::shared_ptr< This > | shared_ptr |
Public Types inherited from gtsam::Factor | |
typedef KeyVector::const_iterator | const_iterator |
Const iterator over keys. More... | |
typedef KeyVector::iterator | iterator |
Iterator over keys. More... | |
Public Member Functions | |
const Vector3 & | accel () const |
gtsam::NonlinearFactor::shared_ptr | clone () const override |
bool | equals (const NonlinearFactor &e, double tol=1e-9) const override |
Vector | evaluateError (const PoseRTV &x1, const PoseRTV &x2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override |
virtual Vector | evaluateError (const Pose3 &x1, const Pose3 &x2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const |
const Vector3 & | gyro () const |
IMUFactor (const Vector3 &accel, const Vector3 &gyro, double dt, const Key &key1, const Key &key2, const SharedNoiseModel &model) | |
time between measurements More... | |
IMUFactor (const Vector6 &imu_vector, double dt, const Key &key1, const Key &key2, const SharedNoiseModel &model) | |
void | print (const std::string &s="", const gtsam::KeyFormatter &formatter=gtsam::DefaultKeyFormatter) const override |
Vector6 | z () const |
~IMUFactor () override | |
Public Member Functions inherited from gtsam::NoiseModelFactor2< POSE, POSE > | |
virtual Vector | evaluateError (const X1 &, const X2 &, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const =0 |
Key | key1 () const |
Key | key2 () const |
NoiseModelFactor2 () | |
NoiseModelFactor2 (const SharedNoiseModel &noiseModel, Key j1, Key j2) | |
Vector | unwhitenedError (const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override |
~NoiseModelFactor2 () override | |
Public Member Functions inherited from gtsam::NoiseModelFactor | |
shared_ptr | cloneWithNewNoiseModel (const SharedNoiseModel newNoise) const |
size_t | dim () const override |
double | error (const Values &c) const override |
boost::shared_ptr< GaussianFactor > | linearize (const Values &x) const override |
const SharedNoiseModel & | noiseModel () const |
access to the noise model More... | |
NoiseModelFactor () | |
template<typename CONTAINER > | |
NoiseModelFactor (const SharedNoiseModel &noiseModel, const CONTAINER &keys) | |
Vector | unweightedWhitenedError (const Values &c) const |
double | weight (const Values &c) const |
Vector | whitenedError (const Values &c) const |
~NoiseModelFactor () override | |
Public Member Functions inherited from gtsam::NonlinearFactor | |
NonlinearFactor () | |
template<typename CONTAINER > | |
NonlinearFactor (const CONTAINER &keys) | |
virtual | ~NonlinearFactor () |
virtual bool | active (const Values &) const |
shared_ptr | rekey (const std::map< Key, Key > &rekey_mapping) const |
shared_ptr | rekey (const KeyVector &new_keys) const |
Public Member Functions inherited from gtsam::Factor | |
virtual | ~Factor ()=default |
Default destructor. More... | |
Key | front () const |
First key. More... | |
Key | back () const |
Last key. More... | |
const_iterator | find (Key key) const |
find More... | |
const KeyVector & | keys () const |
Access the factor's involved variable keys. More... | |
const_iterator | begin () const |
const_iterator | end () const |
size_t | size () const |
virtual void | printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const |
print only keys More... | |
KeyVector & | keys () |
iterator | begin () |
iterator | end () |
Protected Attributes | |
Vector3 | accel_ |
double | dt_ |
Vector3 | gyro_ |
Protected Attributes inherited from gtsam::NoiseModelFactor | |
SharedNoiseModel | noiseModel_ |
Protected Attributes inherited from gtsam::Factor | |
KeyVector | keys_ |
The keys involved in this factor. More... | |
Static Private Member Functions | |
static Vector6 | predict_proxy (const PoseRTV &x1, const PoseRTV &x2, double dt, const Vector6 &meas) |
Additional Inherited Members | |
Protected Types inherited from gtsam::NoiseModelFactor2< POSE, POSE > | |
typedef NoiseModelFactor | Base |
typedef NoiseModelFactor2< POSE, POSE > | This |
Protected Types inherited from gtsam::NoiseModelFactor | |
typedef NonlinearFactor | Base |
typedef NoiseModelFactor | This |
Protected Types inherited from gtsam::NonlinearFactor | |
typedef Factor | Base |
typedef NonlinearFactor | This |
Protected Member Functions inherited from gtsam::NoiseModelFactor | |
NoiseModelFactor (const SharedNoiseModel &noiseModel) | |
Protected Member Functions inherited from gtsam::Factor | |
Factor () | |
template<typename CONTAINER > | |
Factor (const CONTAINER &keys) | |
template<typename ITERATOR > | |
Factor (ITERATOR first, ITERATOR last) | |
bool | equals (const This &other, double tol=1e-9) const |
check equality More... | |
Static Protected Member Functions inherited from gtsam::Factor | |
template<typename CONTAINER > | |
static Factor | FromKeys (const CONTAINER &keys) |
template<typename ITERATOR > | |
static Factor | FromIterators (ITERATOR first, ITERATOR last) |
Class that represents integrating IMU measurements over time for dynamic systems Templated to allow for different key types, but variables all assumed to be PoseRTV
Definition at line 21 of file IMUFactor.h.
typedef NoiseModelFactor2<POSE, POSE> gtsam::IMUFactor< POSE >::Base |
Definition at line 23 of file IMUFactor.h.
typedef IMUFactor<POSE> gtsam::IMUFactor< POSE >::This |
Definition at line 24 of file IMUFactor.h.
|
inline |
|
inline |
Full IMU vector specification
Definition at line 40 of file IMUFactor.h.
|
inlineoverride |
Definition at line 44 of file IMUFactor.h.
|
inline |
Definition at line 70 of file IMUFactor.h.
|
inlineoverridevirtual |
Reimplemented from gtsam::NonlinearFactor.
Definition at line 47 of file IMUFactor.h.
|
inlineoverridevirtual |
Check if two factors are equal
Reimplemented from gtsam::NoiseModelFactor.
Definition at line 52 of file IMUFactor.h.
|
inlineoverride |
Error evaluation with optional derivatives - calculates z - h(x1,x2)
Definition at line 77 of file IMUFactor.h.
|
inlinevirtual |
dummy version that fails for non-dynamic poses
Definition at line 89 of file IMUFactor.h.
|
inline |
Definition at line 69 of file IMUFactor.h.
|
inlinestaticprivate |
copy of the measurement function formulated for numerical derivatives
Definition at line 98 of file IMUFactor.h.
|
inlineoverridevirtual |
|
inline |
Definition at line 71 of file IMUFactor.h.
|
protected |
measurements from the IMU
Definition at line 29 of file IMUFactor.h.
|
protected |
Definition at line 30 of file IMUFactor.h.
|
protected |
Definition at line 29 of file IMUFactor.h.