#include <LinearContainerFactor.h>
Public Types | |
typedef boost::shared_ptr< This > | shared_ptr |
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... | |
Public Member Functions | |
NonlinearFactor::shared_ptr | clone () const override |
GTSAM_EXPORT size_t | dim () const override |
GTSAM_EXPORT bool | equals (const NonlinearFactor &f, double tol=1e-9) const override |
GTSAM_EXPORT double | error (const Values &c) const override |
const GaussianFactor::shared_ptr & | factor () const |
bool | hasLinearizationPoint () const |
GTSAM_EXPORT bool | isHessian () const |
GTSAM_EXPORT bool | isJacobian () const |
GTSAM_EXPORT | LinearContainerFactor (const JacobianFactor &factor, const Values &linearizationPoint=Values()) |
GTSAM_EXPORT | LinearContainerFactor (const HessianFactor &factor, const Values &linearizationPoint=Values()) |
GTSAM_EXPORT | LinearContainerFactor (const GaussianFactor::shared_ptr &factor, const Values &linearizationPoint=Values()) |
const boost::optional< Values > & | linearizationPoint () const |
GTSAM_EXPORT GaussianFactor::shared_ptr | linearize (const Values &c) const override |
GTSAM_EXPORT GaussianFactor::shared_ptr | negateToGaussian () const |
GTSAM_EXPORT NonlinearFactor::shared_ptr | negateToNonlinear () const |
GTSAM_EXPORT void | print (const std::string &s="", const KeyFormatter &keyFormatter=gtsam::DefaultKeyFormatter) const override |
GTSAM_EXPORT boost::shared_ptr< HessianFactor > | toHessian () const |
GTSAM_EXPORT boost::shared_ptr< JacobianFactor > | toJacobian () const |
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 | ~NonlinearFactor () |
virtual bool | active (const Values &) 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 () |
Static Public Member Functions | |
static GTSAM_EXPORT NonlinearFactorGraph | ConvertLinearGraph (const GaussianFactorGraph &linear_graph, const Values &linearizationPoint=Values()) |
Protected Types | |
typedef NonlinearFactor | Base |
typedef LinearContainerFactor | This |
Protected Types inherited from gtsam::NonlinearFactor | |
typedef Factor | Base |
typedef NonlinearFactor | This |
Protected Member Functions | |
GTSAM_EXPORT void | initializeLinearizationPoint (const Values &linearizationPoint) |
LinearContainerFactor () | |
GTSAM_EXPORT | LinearContainerFactor (const GaussianFactor::shared_ptr &factor, const boost::optional< Values > &linearizationPoint) |
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... | |
Protected Attributes | |
GaussianFactor::shared_ptr | factor_ |
boost::optional< Values > | linearizationPoint_ |
Protected Attributes inherited from gtsam::Factor | |
KeyVector | keys_ |
The keys involved in this factor. More... | |
Private Member Functions | |
template<class ARCHIVE > | |
void | serialize (ARCHIVE &ar, const unsigned int) |
Friends | |
class | boost::serialization::access |
Additional Inherited Members | |
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) |
Dummy version of a generic linear factor to be injected into a nonlinear factor graph
This factor does have the ability to perform relinearization under small-angle and linearity assumptions if a linearization point is added.
Definition at line 26 of file LinearContainerFactor.h.
|
protected |
Definition at line 39 of file LinearContainerFactor.h.
typedef boost::shared_ptr<This> gtsam::LinearContainerFactor::shared_ptr |
Definition at line 44 of file LinearContainerFactor.h.
|
protected |
Definition at line 40 of file LinearContainerFactor.h.
|
inlineprotected |
Default constructor - necessary for serialization
Definition at line 33 of file LinearContainerFactor.h.
|
protected |
direct copy constructor
Definition at line 29 of file LinearContainerFactor.cpp.
gtsam::LinearContainerFactor::LinearContainerFactor | ( | const JacobianFactor & | factor, |
const Values & | linearizationPoint = Values() |
||
) |
Primary constructor: store a linear factor with optional linearization point
Definition at line 35 of file LinearContainerFactor.cpp.
gtsam::LinearContainerFactor::LinearContainerFactor | ( | const HessianFactor & | factor, |
const Values & | linearizationPoint = Values() |
||
) |
Primary constructor: store a linear factor with optional linearization point
Definition at line 42 of file LinearContainerFactor.cpp.
gtsam::LinearContainerFactor::LinearContainerFactor | ( | const GaussianFactor::shared_ptr & | factor, |
const Values & | linearizationPoint = Values() |
||
) |
Constructor from shared_ptr
Definition at line 49 of file LinearContainerFactor.cpp.
|
inlineoverridevirtual |
Creates a shared_ptr clone of the factor - needs to be specialized to allow for subclasses
Clones the underlying linear factor
Reimplemented from gtsam::NonlinearFactor.
Definition at line 119 of file LinearContainerFactor.h.
|
static |
Utility function for converting linear graphs to nonlinear graphs consisting of LinearContainerFactors.
Definition at line 168 of file LinearContainerFactor.cpp.
|
overridevirtual |
get the dimension of the factor: rows of linear factor
Implements gtsam::NonlinearFactor.
Definition at line 96 of file LinearContainerFactor.cpp.
|
overridevirtual |
Check if two factors are equal
Reimplemented from gtsam::NonlinearFactor.
Definition at line 65 of file LinearContainerFactor.cpp.
|
overridevirtual |
Calculate the nonlinear error for the factor, where the error is computed by passing the delta between linearization point and c, where delta = linearizationPoint_.localCoordinates(c), into the error function of the stored linear factor.
Implements gtsam::NonlinearFactor.
Definition at line 77 of file LinearContainerFactor.cpp.
|
inline |
Definition at line 57 of file LinearContainerFactor.h.
|
inline |
Definition at line 125 of file LinearContainerFactor.h.
|
protected |
Definition at line 17 of file LinearContainerFactor.cpp.
bool gtsam::LinearContainerFactor::isHessian | ( | ) | const |
Definition at line 141 of file LinearContainerFactor.cpp.
bool gtsam::LinearContainerFactor::isJacobian | ( | ) | const |
Simple checks whether this is a Jacobian or Hessian factor
Definition at line 136 of file LinearContainerFactor.cpp.
|
inline |
Extract the linearization point used in recalculating error
Definition at line 83 of file LinearContainerFactor.h.
|
overridevirtual |
Linearize to a GaussianFactor, with method depending on the presence of a linearizationPoint
The relinearization approach used computes a linear delta between the original linearization point and the new values c, where delta = linearizationPoint_.localCoordinates(c), and substitutes this change into the system. This substitution is only really valid for linear variable manifolds, and for any variables based on a non-commutative manifold (such as Pose2, Pose3), the relinearized version will be effective for only small angles.
TODO: better approximation of relinearization TODO: switchable modes for approximation technique
Implements gtsam::NonlinearFactor.
Definition at line 104 of file LinearContainerFactor.cpp.
GaussianFactor::shared_ptr gtsam::LinearContainerFactor::negateToGaussian | ( | ) | const |
Creates an anti-factor directly
Definition at line 156 of file LinearContainerFactor.cpp.
NonlinearFactor::shared_ptr gtsam::LinearContainerFactor::negateToNonlinear | ( | ) | const |
Creates the equivalent anti-factor as another LinearContainerFactor.
Definition at line 162 of file LinearContainerFactor.cpp.
|
overridevirtual |
|
inlineprivate |
Definition at line 154 of file LinearContainerFactor.h.
HessianFactor::shared_ptr gtsam::LinearContainerFactor::toHessian | ( | ) | const |
Casts to HessianFactor
Definition at line 151 of file LinearContainerFactor.cpp.
JacobianFactor::shared_ptr gtsam::LinearContainerFactor::toJacobian | ( | ) | const |
Casts to JacobianFactor
Definition at line 146 of file LinearContainerFactor.cpp.
|
friend |
Serialization function
Definition at line 152 of file LinearContainerFactor.h.
|
protected |
Definition at line 29 of file LinearContainerFactor.h.
|
protected |
Definition at line 30 of file LinearContainerFactor.h.