Public Types | Public Member Functions | Private Attributes | List of all members
gtsam::ConstantVelocityFactor Class Reference

#include <ConstantVelocityFactor.h>

Inheritance diagram for gtsam::ConstantVelocityFactor:
Inheritance graph
[legend]

Public Types

using Base = NoiseModelFactor2< NavState, NavState >
 
- Public Types inherited from gtsam::NoiseModelFactor2< NavState, NavState >
typedef NavState X1
 
typedef NavState X2
 
- Public Types inherited from gtsam::NoiseModelFactor
typedef boost::shared_ptr< Thisshared_ptr
 
- Public Types inherited from gtsam::NonlinearFactor
typedef boost::shared_ptr< Thisshared_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

 ConstantVelocityFactor (Key i, Key j, double dt, const SharedNoiseModel &model)
 
gtsam::Vector evaluateError (const NavState &x1, const NavState &x2, boost::optional< gtsam::Matrix & > H1=boost::none, boost::optional< gtsam::Matrix & > H2=boost::none) const override
 Caclulate error: (x2 - x1.update(dt))) where X1 and X1 are NavStates and dt is the time difference in seconds between the states. More...
 
 ~ConstantVelocityFactor () override
 
- Public Member Functions inherited from gtsam::NoiseModelFactor2< NavState, NavState >
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
 
bool equals (const NonlinearFactor &f, double tol=1e-9) const override
 
double error (const Values &c) const override
 
boost::shared_ptr< GaussianFactorlinearize (const Values &x) const override
 
const SharedNoiseModelnoiseModel () 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
 
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
 
virtual shared_ptr clone () 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...
 
KeyVectorkeys ()
 
iterator begin ()
 
iterator end ()
 
virtual void printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print only keys More...
 
Key front () const
 First key. More...
 
Key back () const
 Last key. More...
 
const_iterator find (Key key) const
 find More...
 
const KeyVectorkeys () const
 Access the factor's involved variable keys. More...
 
const_iterator begin () const
 
const_iterator end () const
 
size_t size () const
 

Private Attributes

double dt_
 

Additional Inherited Members

- Protected Types inherited from gtsam::NoiseModelFactor2< NavState, NavState >
typedef NoiseModelFactor Base
 
typedef NoiseModelFactor2< NavState, NavStateThis
 
- 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)
 
- Protected Attributes inherited from gtsam::NoiseModelFactor
SharedNoiseModel noiseModel_
 
- Protected Attributes inherited from gtsam::Factor
KeyVector keys_
 The keys involved in this factor. More...
 

Detailed Description

Binary factor for applying a constant velocity model to a moving body represented as a NavState. The only measurement is dt, the time delta between the states.

Definition at line 27 of file ConstantVelocityFactor.h.

Member Typedef Documentation

Definition at line 31 of file ConstantVelocityFactor.h.

Constructor & Destructor Documentation

gtsam::ConstantVelocityFactor::ConstantVelocityFactor ( Key  i,
Key  j,
double  dt,
const SharedNoiseModel model 
)
inline

Definition at line 34 of file ConstantVelocityFactor.h.

gtsam::ConstantVelocityFactor::~ConstantVelocityFactor ( )
inlineoverride

Definition at line 36 of file ConstantVelocityFactor.h.

Member Function Documentation

gtsam::Vector gtsam::ConstantVelocityFactor::evaluateError ( const NavState x1,
const NavState x2,
boost::optional< gtsam::Matrix & >  H1 = boost::none,
boost::optional< gtsam::Matrix & >  H2 = boost::none 
) const
inlineoverride

Caclulate error: (x2 - x1.update(dt))) where X1 and X1 are NavStates and dt is the time difference in seconds between the states.

Parameters
x1NavState for key a
x2NavState for key b
H1optional jacobian in x1
H2optional jacobian in x2
Returns
* Vector

Definition at line 48 of file ConstantVelocityFactor.h.

Member Data Documentation

double gtsam::ConstantVelocityFactor::dt_
private

Definition at line 28 of file ConstantVelocityFactor.h.


The documentation for this class was generated from the following file:


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