gtsam  3.2.0
gtsam
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
gtsam::NonlinearFactor Class Referenceabstract

Detailed Description

Nonlinear factor base class.

Templated on a values structure type. The values structures are typically more general than just vectors, e.g., Rot3 or Pose3, which are objects in non-linear manifolds (Lie groups).

+ Inheritance diagram for gtsam::NonlinearFactor:

Standard Constructors

 NonlinearFactor ()
 Default constructor for I/O only.
 
template<typename CONTAINER >
 NonlinearFactor (const CONTAINER &keys)
 Constructor from a collection of the keys involved in this factor.
 

Testable

virtual void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
 print
 
virtual bool equals (const NonlinearFactor &f, double tol=1e-9) const
 Check if two factors are equal.
 

Standard Interface

virtual ~NonlinearFactor ()
 Destructor.
 
virtual double error (const Values &c) const =0
 Calculate the error of the factor This is typically equal to log-likelihood, e.g. More...
 
virtual size_t dim () const =0
 get the dimension of the factor (number of rows on linearization)
 
virtual bool active (const Values &c) const
 Checks whether a factor should be used based on a set of values. More...
 
virtual boost::shared_ptr
< GaussianFactor
linearize (const Values &c) const =0
 linearize to a GaussianFactor
 
virtual shared_ptr clone () const
 Create a symbolic factor using the given ordering to determine the variable indices. More...
 
shared_ptr rekey (const std::map< Key, Key > &rekey_mapping) const
 Creates a shared_ptr clone of the factor with different keys using a map from old->new keys.
 
shared_ptr rekey (const std::vector< Key > &new_keys) const
 Clones a factor and fully replaces its keys. More...
 

Public Types

typedef boost::shared_ptr< Thisshared_ptr
 
- Public Types inherited from gtsam::Factor
typedef FastVector< Key >::iterator iterator
 Iterator over keys.
 
typedef FastVector< Key >
::const_iterator 
const_iterator
 Const iterator over keys.
 

Protected Types

typedef Factor Base
 
typedef NonlinearFactor This
 

Additional Inherited Members

- Public Member Functions inherited from gtsam::Factor
Key front () const
 First key.
 
Key back () const
 Last key.
 
const_iterator find (Key key) const
 find
 
const FastVector< Key > & keys () const
 Access the factor's involved variable keys.
 
const_iterator begin () const
 Iterator at beginning of involved variable keys.
 
const_iterator end () const
 Iterator at end of involved variable keys.
 
size_t size () const
 
void print (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print
 
void printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print only keys
 
FastVector< Key > & keys ()
 
iterator begin ()
 Iterator at beginning of involved variable keys.
 
iterator end ()
 Iterator at end of involved variable keys.
 
- Protected Member Functions inherited from gtsam::Factor
 Factor ()
 Default constructor for I/O.
 
template<typename CONTAINER >
 Factor (const CONTAINER &keys)
 Construct factor from container of keys. More...
 
template<typename ITERATOR >
 Factor (ITERATOR first, ITERATOR last)
 Construct factor from iterator keys. More...
 
bool equals (const This &other, double tol=1e-9) const
 check equality
 
- Static Protected Member Functions inherited from gtsam::Factor
template<typename CONTAINER >
static Factor FromKeys (const CONTAINER &keys)
 Construct factor from container of keys. More...
 
template<typename ITERATOR >
static Factor FromIterators (ITERATOR first, ITERATOR last)
 Construct factor from iterator keys. More...
 
- Protected Attributes inherited from gtsam::Factor
FastVector< Keykeys_
 The keys involved in this factor.
 

Member Function Documentation

virtual bool gtsam::NonlinearFactor::active ( const Values c) const
inlinevirtual

Checks whether a factor should be used based on a set of values.

This is primarily used to implment inequality constraints that require a variable active set. For all others, the default implementation returning true solves this problem.

In an inequality/bounding constraint, this active() returns true when the constraint is NOT fulfilled.

Returns
true if the constraint is active

Reimplemented in gtsam::BoundingConstraint2< VALUE1, VALUE2 >, gtsam::AntiFactor, and gtsam::BoundingConstraint1< VALUE >.

virtual double gtsam::NonlinearFactor::error ( const Values c) const
pure virtual

Calculate the error of the factor This is typically equal to log-likelihood, e.g.

\( 0.5(h(x)-z)^2/sigma^2 \) in case of Gaussian. You can override this for systems with unusual noise models.

Implemented in gtsam::NoiseModelFactor, gtsam::SmartProjectionPoseFactor< POSE, LANDMARK, CALIBRATION >, gtsam::NonlinearEquality< VALUE >, gtsam::WhiteNoiseFactor, gtsam::AntiFactor, and gtsam::LinearContainerFactor.

shared_ptr gtsam::NonlinearFactor::rekey ( const std::vector< Key > &  new_keys) const
inline

Clones a factor and fully replaces its keys.

Parameters
new_keysis the full replacement set of keys

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