#include <CombinedImuFactor.h>
Public Types | |
typedef std::shared_ptr< CombinedImuFactor > | 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 |
CombinedImuFactor () | |
CombinedImuFactor (Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias_i, Key bias_j, const PreintegratedCombinedMeasurements &preintegratedMeasurements) | |
Vector | evaluateError (const Pose3 &pose_i, const Vector3 &vel_i, const Pose3 &pose_j, const Vector3 &vel_j, const imuBias::ConstantBias &bias_i, const imuBias::ConstantBias &bias_j, OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3, OptionalMatrixType H4, OptionalMatrixType H5, OptionalMatrixType H6) const override |
vector of errors More... | |
const PreintegratedCombinedMeasurements & | preintegratedMeasurements () const |
~CombinedImuFactor () 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, imuBias::ConstantBias > | Base |
typedef CombinedImuFactor | This |
Private Attributes | |
PreintegratedCombinedMeasurements | _PIM_ |
Testable | |
implement functions needed for 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 |
equals More... | |
GTSAM_EXPORT friend std::ostream & | operator<< (std::ostream &os, const CombinedImuFactor &) |
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... | |
CombinedImuFactor is a 6-ways factor involving previous state (pose and velocity of the vehicle, as well as bias at previous time step), and current state (pose, velocity, bias at current time step). Following the pre- integration scheme proposed in [2], the CombinedImuFactor includes many IMU measurements, which are "summarized" using the PreintegratedCombinedMeasurements class. There are 3 main differences wrpt the ImuFactor class: 1) The factor is 6-ways, meaning that it also involves both biases (previous and current time step).Therefore, the factor internally imposes the biases to be slowly varying; in particular, the matrices "biasAccCovariance" and "biasOmegaCovariance" described the random walk that models bias evolution. 2) The preintegration covariance takes into account the noise in the bias estimate used for integration. 3) The covariance matrix of the PreintegratedCombinedMeasurements preserves the correlation between the bias uncertainty and the preintegrated measurements uncertainty.
Definition at line 209 of file CombinedImuFactor.h.
|
private |
Definition at line 217 of file CombinedImuFactor.h.
typedef std::shared_ptr<CombinedImuFactor> gtsam::CombinedImuFactor::shared_ptr |
Shorthand for a smart pointer to a factor
Definition at line 229 of file CombinedImuFactor.h.
|
private |
Definition at line 214 of file CombinedImuFactor.h.
|
inline |
Default constructor - only use for serialization
Definition at line 233 of file CombinedImuFactor.h.
gtsam::CombinedImuFactor::CombinedImuFactor | ( | Key | pose_i, |
Key | vel_i, | ||
Key | pose_j, | ||
Key | vel_j, | ||
Key | bias_i, | ||
Key | bias_j, | ||
const PreintegratedCombinedMeasurements & | preintegratedMeasurements | ||
) |
Constructor
pose_i | Previous pose key |
vel_i | Previous velocity key |
pose_j | Current pose key |
vel_j | Current velocity key |
bias_i | Previous bias key |
bias_j | Current bias key |
PreintegratedCombinedMeasurements | Combined IMU measurements |
Definition at line 202 of file CombinedImuFactor.cpp.
|
inlineoverride |
Definition at line 249 of file CombinedImuFactor.h.
|
overridevirtual |
Reimplemented from gtsam::NonlinearFactor.
Definition at line 210 of file CombinedImuFactor.cpp.
|
overridevirtual |
equals
Reimplemented from gtsam::NonlinearFactor.
Definition at line 228 of file CombinedImuFactor.cpp.
|
override |
vector of errors
implement functions needed to derive from Factor
Definition at line 234 of file CombinedImuFactor.cpp.
|
inline |
Access the preintegrated measurements.
Definition at line 271 of file CombinedImuFactor.h.
|
overridevirtual |
|
friend |
Definition at line 299 of file CombinedImuFactor.cpp.
|
private |
Definition at line 219 of file CombinedImuFactor.h.