#include <ImuFactor.h>
Public Types | |
typedef std::shared_ptr< ImuFactor > | shared_ptr |
![]() | |
using | ValueType = typename std::tuple_element< I - 1, std::tuple< ValueTypes... > >::type |
![]() | |
typedef std::shared_ptr< This > | shared_ptr |
![]() | |
typedef std::shared_ptr< This > | shared_ptr |
![]() | |
typedef KeyVector::const_iterator | const_iterator |
Const iterator over keys. More... | |
typedef KeyVector::iterator | iterator |
Iterator over keys. More... | |
Public Member Functions | |
gtsam::NonlinearFactor::shared_ptr | clone () const override |
Vector | evaluateError (const Pose3 &pose_i, const Vector3 &vel_i, const Pose3 &pose_j, const Vector3 &vel_j, const imuBias::ConstantBias &bias_i, OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3, OptionalMatrixType H4, OptionalMatrixType H5) const override |
vector of errors More... | |
ImuFactor () | |
ImuFactor (Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias, const PreintegratedImuMeasurements &preintegratedMeasurements) | |
const PreintegratedImuMeasurements & | preintegratedMeasurements () const |
~ImuFactor () override | |
![]() | |
Key | key () const |
virtual Vector | unwhitenedError (const Values &x, OptionalMatrixVecType H=nullptr) const =0 |
Vector | unwhitenedError (const Values &x, std::vector< Matrix > &H) const |
~NoiseModelFactorN () override | |
NoiseModelFactorN () | |
Default Constructor for I/O. More... | |
NoiseModelFactorN (const SharedNoiseModel &noiseModel, KeyType< ValueTypes >... keys) | |
NoiseModelFactorN (const SharedNoiseModel &noiseModel, CONTAINER keys) | |
Vector | unwhitenedError (const Values &x, OptionalMatrixVecType H=nullptr) const override |
virtual Vector | evaluateError (const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0 |
Vector | evaluateError (const ValueTypes &... x, MatrixTypeT< ValueTypes > &... H) const |
Vector | evaluateError (const ValueTypes &... x) const |
AreAllMatrixRefs< Vector, OptionalJacArgs... > | evaluateError (const ValueTypes &... x, OptionalJacArgs &&... H) const |
AreAllMatrixPtrs< Vector, OptionalJacArgs... > | evaluateError (const ValueTypes &... x, OptionalJacArgs &&... H) const |
Key | key1 () const |
Key | key2 () const |
Key | key3 () const |
Key | key4 () const |
Key | key5 () const |
Key | key6 () const |
![]() | |
shared_ptr | cloneWithNewNoiseModel (const SharedNoiseModel newNoise) const |
size_t | dim () const override |
bool | equals (const NonlinearFactor &f, double tol=1e-9) const override |
double | error (const HybridValues &c) const override |
virtual double | error (const Values &c) const |
double | error (const Values &c) const override |
std::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) | |
void | print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override |
Vector | unweightedWhitenedError (const Values &c) const |
Vector | unwhitenedError (const Values &x, std::vector< Matrix > &H) const |
double | weight (const Values &c) const |
Vector | whitenedError (const Values &c) const |
~NoiseModelFactor () override | |
![]() | |
NonlinearFactor () | |
template<typename CONTAINER > | |
NonlinearFactor (const CONTAINER &keys) | |
double | error (const HybridValues &c) const override |
virtual bool | active (const Values &) const |
virtual shared_ptr | rekey (const std::map< Key, Key > &rekey_mapping) const |
virtual shared_ptr | rekey (const KeyVector &new_keys) const |
virtual bool | sendable () const |
![]() | |
virtual | ~Factor ()=default |
Default destructor. More... | |
bool | empty () const |
Whether the factor is empty (involves zero variables). 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... | |
bool | equals (const This &other, double tol=1e-9) const |
check equality More... | |
KeyVector & | keys () |
iterator | begin () |
iterator | end () |
Private Types | |
typedef NoiseModelFactorN< Pose3, Vector3, Pose3, Vector3, imuBias::ConstantBias > | Base |
typedef ImuFactor | This |
Private Attributes | |
PreintegratedImuMeasurements | _PIM_ |
Testable | |
void | print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override |
print More... | |
bool | equals (const NonlinearFactor &expected, double tol=1e-9) const override |
GTSAM_EXPORT friend std::ostream & | operator<< (std::ostream &os, const ImuFactor &) |
Additional Inherited Members | |
![]() | |
constexpr static auto | N |
N is the number of variables (N-way factor) More... | |
![]() | |
using | Base = NoiseModelFactor |
using | KeyType = Key |
using | MatrixTypeT = Matrix |
using | OptionalMatrixTypeT = Matrix * |
using | This = NoiseModelFactorN< ValueTypes... > |
using | IsConvertible = typename std::enable_if< std::is_convertible< From, To >::value, void >::type |
using | IndexIsValid = typename std::enable_if<(I >=1) &&(I<=N), void >::type |
using | ContainerElementType = typename std::decay< decltype(*std::declval< Container >().begin())>::type |
using | IsContainerOfKeys = IsConvertible< ContainerElementType< Container >, Key > |
using | AreAllMatrixRefs = std::enable_if_t<(... &&std::is_convertible< Args, Matrix & >::value), Ret > |
using | IsMatrixPointer = std::is_same< typename std::decay_t< Arg >, Matrix * > |
using | IsNullpointer = std::is_same< typename std::decay_t< Arg >, std::nullptr_t > |
using | AreAllMatrixPtrs = std::enable_if_t<(... &&(IsMatrixPointer< Args >::value||IsNullpointer< Args >::value)), Ret > |
![]() | |
typedef NonlinearFactor | Base |
typedef NoiseModelFactor | This |
![]() | |
typedef Factor | Base |
typedef NonlinearFactor | This |
![]() | |
NoiseModelFactor (const SharedNoiseModel &noiseModel) | |
![]() | |
Factor () | |
template<typename CONTAINER > | |
Factor (const CONTAINER &keys) | |
template<typename ITERATOR > | |
Factor (ITERATOR first, ITERATOR last) | |
![]() | |
template<typename CONTAINER > | |
static Factor | FromKeys (const CONTAINER &keys) |
template<typename ITERATOR > | |
static Factor | FromIterators (ITERATOR first, ITERATOR last) |
![]() | |
SharedNoiseModel | noiseModel_ |
![]() | |
KeyVector | keys_ |
The keys involved in this factor. More... | |
ImuFactor is a 5-ways factor involving previous state (pose and velocity of the vehicle at previous time step), current state (pose and velocity at current time step), and the bias estimate. Following the preintegration scheme proposed in [2], the ImuFactor includes many IMU measurements, which are "summarized" using the PreintegratedImuMeasurements class. Note that this factor does not model "temporal consistency" of the biases (which are usually slowly varying quantities), which is up to the caller. See also CombinedImuFactor for a class that does this for you.
Definition at line 170 of file ImuFactor.h.
|
private |
Definition at line 176 of file ImuFactor.h.
typedef std::shared_ptr<ImuFactor> gtsam::ImuFactor::shared_ptr |
Shorthand for a smart pointer to a factor
Definition at line 189 of file ImuFactor.h.
|
private |
Definition at line 174 of file ImuFactor.h.
|
inline |
Default constructor - only use for serialization
Definition at line 193 of file ImuFactor.h.
gtsam::ImuFactor::ImuFactor | ( | Key | pose_i, |
Key | vel_i, | ||
Key | pose_j, | ||
Key | vel_j, | ||
Key | bias, | ||
const PreintegratedImuMeasurements & | preintegratedMeasurements | ||
) |
Constructor
pose_i | Previous pose key |
vel_i | Previous velocity key |
pose_j | Current pose key |
vel_j | Current velocity key |
bias | Previous bias key |
preintegratedMeasurements | The preintegreated measurements since the last pose. |
Definition at line 116 of file ImuFactor.cpp.
|
inlineoverride |
Definition at line 208 of file ImuFactor.h.
|
overridevirtual |
Reimplemented from gtsam::NonlinearFactor.
Definition at line 123 of file ImuFactor.cpp.
|
overridevirtual |
Check if two factors are equal
Reimplemented from gtsam::NonlinearFactor.
Definition at line 145 of file ImuFactor.cpp.
|
override |
vector of errors
implement functions needed to derive from Factor
Definition at line 153 of file ImuFactor.cpp.
|
inline |
Access the preintegrated measurements.
Definition at line 224 of file ImuFactor.h.
|
overridevirtual |
|
friend |
Definition at line 129 of file ImuFactor.cpp.
|
private |
Definition at line 178 of file ImuFactor.h.