Public Member Functions | Private Types | Private Attributes | List of all members
gtsam::KarcherMeanFactor< T > Class Template Reference

#include <KarcherMeanFactor.h>

Inheritance diagram for gtsam::KarcherMeanFactor< T >:
Inheritance graph
[legend]

Public Member Functions

size_t dim () const override
 get the dimension of the factor (number of rows on linearization) More...
 
double error (const Values &c) const override
 Calculate the error of the factor: always zero. More...
 
template<typename CONTAINER >
 KarcherMeanFactor (const CONTAINER &keys, int d=D, boost::optional< double > beta=boost::none)
 
boost::shared_ptr< GaussianFactorlinearize (const Values &c) const override
 linearize to a GaussianFactor More...
 
 ~KarcherMeanFactor () override
 Destructor. More...
 
- Public Member Functions inherited from gtsam::NonlinearFactor
 NonlinearFactor ()
 
template<typename CONTAINER >
 NonlinearFactor (const CONTAINER &keys)
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 
virtual bool equals (const NonlinearFactor &f, double tol=1e-9) const
 
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...
 
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
 
virtual void printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print only keys More...
 
KeyVectorkeys ()
 
iterator begin ()
 
iterator end ()
 

Private Types

enum  { D = traits<T>::dimension }
 

Private Attributes

size_t d_
 
boost::shared_ptr< JacobianFactorwhitenedJacobian_
 Constant Jacobian made of d*d identity matrices. More...
 

Additional Inherited Members

- 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::NonlinearFactor
typedef Factor Base
 
typedef NonlinearFactor This
 
- 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::Factor
KeyVector keys_
 The keys involved in this factor. More...
 

Detailed Description

template<class T>
class gtsam::KarcherMeanFactor< T >

The KarcherMeanFactor creates a constraint on all SO(n) variables with given keys that the Karcher mean (see above) will stay the same. Note the mean itself is irrelevant to the constraint and is not a parameter: the constraint is implemented as enforcing that the sum of local updates is equal to zero, hence creating a rank-dim constraint. Note it is implemented as a soft constraint, as typically it is used to fix a gauge freedom.

Definition at line 45 of file KarcherMeanFactor.h.

Member Enumeration Documentation

template<class T>
anonymous enum
private
Enumerator

Definition at line 47 of file KarcherMeanFactor.h.

Constructor & Destructor Documentation

template<class T >
template<typename CONTAINER >
gtsam::KarcherMeanFactor< T >::KarcherMeanFactor ( const CONTAINER &  keys,
int  d = D,
boost::optional< double >  beta = boost::none 
)

Construct from given keys. If parameter beta is given, it acts as a precision = 1/sigma^2, and the Jacobian will be multiplied with 1/sigma = sqrt(beta).

Definition at line 61 of file KarcherMeanFactor-inl.h.

template<class T>
gtsam::KarcherMeanFactor< T >::~KarcherMeanFactor ( )
inlineoverride

Destructor.

Definition at line 66 of file KarcherMeanFactor.h.

Member Function Documentation

template<class T>
size_t gtsam::KarcherMeanFactor< T >::dim ( ) const
inlineoverridevirtual

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

Implements gtsam::NonlinearFactor.

Definition at line 72 of file KarcherMeanFactor.h.

template<class T>
double gtsam::KarcherMeanFactor< T >::error ( const Values c) const
inlineoverridevirtual

Calculate the error of the factor: always zero.

Implements gtsam::NonlinearFactor.

Definition at line 69 of file KarcherMeanFactor.h.

template<class T>
boost::shared_ptr<GaussianFactor> gtsam::KarcherMeanFactor< T >::linearize ( const Values c) const
inlineoverridevirtual

linearize to a GaussianFactor

Implements gtsam::NonlinearFactor.

Definition at line 75 of file KarcherMeanFactor.h.

Member Data Documentation

template<class T>
size_t gtsam::KarcherMeanFactor< T >::d_
private

Definition at line 50 of file KarcherMeanFactor.h.

template<class T>
boost::shared_ptr<JacobianFactor> gtsam::KarcherMeanFactor< T >::whitenedJacobian_
private

Constant Jacobian made of d*d identity matrices.

Definition at line 53 of file KarcherMeanFactor.h.


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


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