#include <ShonanGaugeFactor.h>
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... | |
boost::shared_ptr< GaussianFactor > | linearize (const Values &c) const override |
linearize to a GaussianFactor More... | |
ShonanGaugeFactor (Key key, size_t p, size_t d=3, boost::optional< double > gamma=boost::none) | |
~ShonanGaugeFactor () 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 KeyVector & | keys () 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... | |
KeyVector & | keys () |
iterator | begin () |
iterator | end () |
Private Attributes | |
size_t | rows_ |
boost::shared_ptr< JacobianFactor > | whitenedJacobian_ |
Constant Jacobian. More... | |
Additional Inherited Members | |
Public Types inherited from gtsam::NonlinearFactor | |
typedef boost::shared_ptr< This > | shared_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... | |
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.
Definition at line 47 of file ShonanGaugeFactor.h.
|
inline |
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).
Definition at line 60 of file ShonanGaugeFactor.h.
|
inlineoverride |
Destructor.
Definition at line 93 of file ShonanGaugeFactor.h.
|
inlineoverridevirtual |
get the dimension of the factor (number of rows on linearization)
Implements gtsam::NonlinearFactor.
Definition at line 99 of file ShonanGaugeFactor.h.
|
inlineoverridevirtual |
Calculate the error of the factor: always zero.
Implements gtsam::NonlinearFactor.
Definition at line 96 of file ShonanGaugeFactor.h.
|
inlineoverridevirtual |
linearize to a GaussianFactor
Implements gtsam::NonlinearFactor.
Definition at line 102 of file ShonanGaugeFactor.h.
|
private |
Definition at line 49 of file ShonanGaugeFactor.h.
|
private |
Constant Jacobian.
Definition at line 52 of file ShonanGaugeFactor.h.