Public Member Functions | Protected Attributes | Private Types | List of all members
NonlinearMotionModel Class Reference
Inheritance diagram for NonlinearMotionModel:
Inheritance graph
[legend]

Public Member Functions

size_t dim () const override
 
bool equals (const NonlinearFactor &f, double tol=1e-9) const override
 
double error (const Values &c) const override
 
Vector evaluateError (const Point2 &p1, const Point2 &p2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
 
Point2 f (const Point2 &x_t0) const
 
Matrix F (const Point2 &x_t0) const
 
boost::shared_ptr< GaussianFactorlinearize (const Values &c) const override
 
 NonlinearMotionModel ()
 
 NonlinearMotionModel (const Symbol &TestKey1, const Symbol &TestKey2)
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 
Matrix QInvSqrt (const Point2 &x_t0) const
 
Vector whitenedError (const Values &c) const
 
 ~NonlinearMotionModel () override
 
- Public Member Functions inherited from gtsam::NoiseModelFactor2< Point2, Point2 >
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
 
const SharedNoiseModelnoiseModel () 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
 
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
 

Protected Attributes

Matrix Q_
 
Matrix Q_invsqrt_
 
- Protected Attributes inherited from gtsam::NoiseModelFactor
SharedNoiseModel noiseModel_
 
- Protected Attributes inherited from gtsam::Factor
KeyVector keys_
 The keys involved in this factor. More...
 

Private Types

typedef NoiseModelFactor2< Point2, Point2Base
 
typedef NonlinearMotionModel This
 

Additional Inherited Members

- Public Types inherited from gtsam::NoiseModelFactor2< Point2, Point2 >
typedef Point2 X1
 
typedef Point2 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...
 
- Protected Types inherited from gtsam::NoiseModelFactor2< Point2, Point2 >
typedef NoiseModelFactor Base
 
typedef NoiseModelFactor2< Point2, Point2This
 
- 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)
 

Detailed Description

Definition at line 94 of file testExtendedKalmanFilter.cpp.

Member Typedef Documentation

Definition at line 96 of file testExtendedKalmanFilter.cpp.

Definition at line 97 of file testExtendedKalmanFilter.cpp.

Constructor & Destructor Documentation

NonlinearMotionModel::NonlinearMotionModel ( )
inline

Definition at line 104 of file testExtendedKalmanFilter.cpp.

NonlinearMotionModel::NonlinearMotionModel ( const Symbol TestKey1,
const Symbol TestKey2 
)
inline

Definition at line 106 of file testExtendedKalmanFilter.cpp.

NonlinearMotionModel::~NonlinearMotionModel ( )
inlineoverride

Definition at line 123 of file testExtendedKalmanFilter.cpp.

Member Function Documentation

size_t NonlinearMotionModel::dim ( ) const
inlineoverridevirtual

get the dimension of the factor (number of rows on linearization)

Reimplemented from gtsam::NoiseModelFactor.

Definition at line 178 of file testExtendedKalmanFilter.cpp.

bool NonlinearMotionModel::equals ( const NonlinearFactor f,
double  tol = 1e-9 
) const
inlineoverridevirtual

Check if two factors are equal. Note type is IndexFactor and needs cast.

Reimplemented from gtsam::NoiseModelFactor.

Definition at line 163 of file testExtendedKalmanFilter.cpp.

double NonlinearMotionModel::error ( const Values c) const
inlineoverridevirtual

calculate the error of the factor Override for systems with unusual noise models

Reimplemented from gtsam::NoiseModelFactor.

Definition at line 172 of file testExtendedKalmanFilter.cpp.

Vector NonlinearMotionModel::evaluateError ( const Point2 p1,
const Point2 p2,
boost::optional< Matrix & >  H1 = boost::none,
boost::optional< Matrix & >  H2 = boost::none 
) const
inlineoverride

vector of errors

Definition at line 213 of file testExtendedKalmanFilter.cpp.

Point2 NonlinearMotionModel::f ( const Point2 x_t0) const
inline

Definition at line 126 of file testExtendedKalmanFilter.cpp.

Matrix NonlinearMotionModel::F ( const Point2 x_t0) const
inline

Definition at line 138 of file testExtendedKalmanFilter.cpp.

boost::shared_ptr<GaussianFactor> NonlinearMotionModel::linearize ( const Values c) const
inlineoverridevirtual

Linearize a non-linearFactor2 to get a GaussianFactor Ax-b h(x1+dx1,x2+dx2)-z = h(x1,x2) + A2*dx1 + A2*dx2 - z Hence b = z - h(x1,x2) = - error_vector(x)

Reimplemented from gtsam::NoiseModelFactor.

Definition at line 192 of file testExtendedKalmanFilter.cpp.

void NonlinearMotionModel::print ( const std::string &  s = "",
const KeyFormatter keyFormatter = DefaultKeyFormatter 
) const
inlineoverridevirtual

Print

Reimplemented from gtsam::NoiseModelFactor.

Definition at line 156 of file testExtendedKalmanFilter.cpp.

Matrix NonlinearMotionModel::QInvSqrt ( const Point2 x_t0) const
inline

Definition at line 150 of file testExtendedKalmanFilter.cpp.

Vector NonlinearMotionModel::whitenedError ( const Values c) const
inline

Vector of errors, whitened !

Definition at line 183 of file testExtendedKalmanFilter.cpp.

Member Data Documentation

Matrix NonlinearMotionModel::Q_
protected

Definition at line 100 of file testExtendedKalmanFilter.cpp.

Matrix NonlinearMotionModel::Q_invsqrt_
protected

Definition at line 101 of file testExtendedKalmanFilter.cpp.


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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:51:48