gtsam 4.1.1
gtsam
gtsam::ShonanGaugeFactor Class Reference

Detailed Description

The ShonanGaugeFactor creates a constraint on a single SO(n) to avoid moving in the stabilizer.

Details: SO(p) contains the p*3 Stiefel matrices of orthogonal frames: we take those to be the 3 columns on the left. The P*P skew-symmetric matrices associated with so(p) can be partitioned as (Appendix B in the ECCV paper): | [w] -K' | | K [g] | where w is the SO(3) space, K are the extra Stiefel diemnsions (wormhole!) and (g)amma are extra dimensions in SO(p) that do not modify the cost function. The latter corresponds to rotations SO(p-d), and so the first few values of p-d for d==3 with their corresponding dimensionality are {0:0, 1:0, 2:1, 3:3, ...}

The ShonanGaugeFactor adds a unit Jacobian to these extra dimensions, essentially restricting the optimization to the Stiefel manifold.

+ Inheritance diagram for gtsam::ShonanGaugeFactor:

Public Member Functions

 ShonanGaugeFactor (Key key, size_t p, size_t d=3, boost::optional< double > gamma=boost::none)
 Construct from key for an SO(p) matrix, for base dimension d (2 or 3) If parameter gamma is given, it acts as a precision = 1/sigma^2, and the Jacobian will be multiplied with 1/sigma = sqrt(gamma).
 
 ~ShonanGaugeFactor () override
 Destructor.
 
double error (const Values &c) const override
 Calculate the error of the factor: always zero. More...
 
size_t dim () const override
 get the dimension of the factor (number of rows on linearization) More...
 
boost::shared_ptr< GaussianFactorlinearize (const Values &c) const override
 linearize to a GaussianFactor More...
 
- Public Member Functions inherited from gtsam::NonlinearFactor
 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.
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 print More...
 
virtual bool equals (const NonlinearFactor &f, double tol=1e-9) const
 Check if two factors are equal. More...
 
virtual ~NonlinearFactor ()
 Destructor.
 
virtual bool active (const Values &) const
 Checks whether a factor should be used based on a set of values. More...
 
virtual shared_ptr clone () const
 Creates a shared_ptr clone of the factor - needs to be specialized to allow for subclasses. More...
 
virtual 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. More...
 
virtual shared_ptr rekey (const KeyVector &new_keys) const
 Clones a factor and fully replaces its keys. More...
 
virtual bool sendable () const
 Should the factor be evaluated in the same thread as the caller This is to enable factors that has shared states (like the Python GIL lock) More...
 
- Public Member Functions inherited from gtsam::Factor
virtual ~Factor ()=default
 Default destructor.
 
KeyVectorkeys ()
 
iterator begin ()
 Iterator at beginning of involved variable keys.
 
iterator end ()
 Iterator at end of involved variable keys.
 
virtual void printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print only keys More...
 
Key front () const
 First key.
 
Key back () const
 Last key.
 
const_iterator find (Key key) const
 find
 
const KeyVectorkeys () 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
 

Additional Inherited Members

- Public Types inherited from gtsam::NonlinearFactor
typedef boost::shared_ptr< Thisshared_ptr
 
- Public Types inherited from gtsam::Factor
typedef KeyVector::iterator iterator
 Iterator over keys.
 
typedef KeyVector::const_iterator const_iterator
 Const iterator over keys.
 
- Protected Types inherited from gtsam::NonlinearFactor
typedef Factor Base
 
typedef NonlinearFactor This
 
- 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
KeyVector keys_
 The keys involved in this factor.
 

Member Function Documentation

◆ dim()

size_t gtsam::ShonanGaugeFactor::dim ( ) const
inlineoverridevirtual

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

Implements gtsam::NonlinearFactor.

◆ error()

double gtsam::ShonanGaugeFactor::error ( const Values c) const
inlineoverridevirtual

Calculate the error of the factor: always zero.

Implements gtsam::NonlinearFactor.

◆ linearize()

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

linearize to a GaussianFactor

Implements gtsam::NonlinearFactor.


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