GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
Public Types | Public Member Functions | Static Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
gtsam::LinearContainerFactor Class Reference

#include <LinearContainerFactor.h>

Inheritance diagram for gtsam::LinearContainerFactor:
Inheritance graph
[legend]
Collaboration diagram for gtsam::LinearContainerFactor:
Collaboration graph
[legend]

Public Types

typedef std::shared_ptr< Thisshared_ptr
 
typedef KeyVector::iterator iterator
 Iterator over keys.
 
typedef KeyVector::const_iterator const_iterator
 Const iterator over keys.
 

Public Member Functions

 LinearContainerFactor ()
 
 LinearContainerFactor (const JacobianFactor &factor, const Values &linearizationPoint=Values())
 
 LinearContainerFactor (const HessianFactor &factor, const Values &linearizationPoint=Values())
 
 LinearContainerFactor (const GaussianFactor::shared_ptr &factor, const Values &linearizationPoint=Values())
 
const GaussianFactor::shared_ptrfactor () const
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=gtsam::DefaultKeyFormatter) const override
 
bool equals (const NonlinearFactor &f, double tol=1e-9) const override
 
double error (const Values &c) const override
 
size_t dim () const override
 
const std::optional< Values > & linearizationPoint () const
 
GaussianFactor::shared_ptr linearize (const Values &c) const override
 
GaussianFactor::shared_ptr negateToGaussian () const
 
NonlinearFactor::shared_ptr negateToNonlinear () const
 
NonlinearFactor::shared_ptr clone () const override
 
NonlinearFactor::shared_ptr rekey (const std::map< Key, Key > &rekey_mapping) const override
 
NonlinearFactor::shared_ptr rekey (const KeyVector &new_keys) const override
 
bool hasLinearizationPoint () const
 Casting syntactic sugar.
 
bool isJacobian () const
 
bool isHessian () const
 
std::shared_ptr< JacobianFactortoJacobian () const
 
std::shared_ptr< HessianFactortoHessian () const
 
Testable
bool equals (const This &other, double tol=1e-9) const
 check equality
 
virtual void printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print only keys
 
Standard Interface
double error (const HybridValues &c) const override
 
virtual bool active (const Values &) const
 
virtual bool sendable () const
 
Standard Interface
bool empty () const
 Whether the factor is empty (involves zero variables).
 
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
 
const_iterator end () const
 
size_t size () const
 
Advanced Interface
KeyVectorkeys ()
 
iterator begin ()
 
iterator end ()
 

Static Public Member Functions

static NonlinearFactorGraph ConvertLinearGraph (const GaussianFactorGraph &linear_graph, const Values &linearizationPoint=Values())
 

Protected Types

typedef NonlinearFactor Base
 
typedef LinearContainerFactor This
 

Protected Member Functions

 LinearContainerFactor (const GaussianFactor::shared_ptr &factor, const std::optional< Values > &linearizationPoint)
 
void initializeLinearizationPoint (const Values &linearizationPoint)
 

Static Protected Member Functions

Standard Constructors
template<typename CONTAINER >
static Factor FromKeys (const CONTAINER &keys)
 
template<typename ITERATOR >
static Factor FromIterators (ITERATOR first, ITERATOR last)
 

Protected Attributes

GaussianFactor::shared_ptr factor_
 
std::optional< ValueslinearizationPoint_
 
KeyVector keys_
 The keys involved in this factor.
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ LinearContainerFactor() [1/5]

gtsam::LinearContainerFactor::LinearContainerFactor ( const GaussianFactor::shared_ptr factor,
const std::optional< Values > &  linearizationPoint 
)
protected

direct copy constructor

◆ LinearContainerFactor() [2/5]

gtsam::LinearContainerFactor::LinearContainerFactor ( )
inline

Default constructor - necessary for serialization

◆ LinearContainerFactor() [3/5]

gtsam::LinearContainerFactor::LinearContainerFactor ( const JacobianFactor factor,
const Values linearizationPoint = Values() 
)

Primary constructor: store a linear factor with optional linearization point

◆ LinearContainerFactor() [4/5]

gtsam::LinearContainerFactor::LinearContainerFactor ( const HessianFactor factor,
const Values linearizationPoint = Values() 
)

Primary constructor: store a linear factor with optional linearization point

◆ LinearContainerFactor() [5/5]

gtsam::LinearContainerFactor::LinearContainerFactor ( const GaussianFactor::shared_ptr factor,
const Values linearizationPoint = Values() 
)

Constructor from shared_ptr

Member Function Documentation

◆ active()

virtual bool gtsam::NonlinearFactor::active ( const Values ) const
inlinevirtualinherited

Checks whether a factor should be used based on a set of values. This is primarily used to implement 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 >.

◆ begin() [1/2]

const_iterator gtsam::Factor::begin ( ) const
inlineinherited

Iterator at beginning of involved variable keys

◆ begin() [2/2]

iterator gtsam::Factor::begin ( )
inlineinherited

Iterator at beginning of involved variable keys

◆ clone()

NonlinearFactor::shared_ptr gtsam::LinearContainerFactor::clone ( ) const
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.

◆ ConvertLinearGraph()

static NonlinearFactorGraph gtsam::LinearContainerFactor::ConvertLinearGraph ( const GaussianFactorGraph linear_graph,
const Values linearizationPoint = Values() 
)
static

Utility function for converting linear graphs to nonlinear graphs consisting of LinearContainerFactors.

◆ dim()

size_t gtsam::LinearContainerFactor::dim ( ) const
overridevirtual

get the dimension of the factor: rows of linear factor

Implements gtsam::NonlinearFactor.

◆ end() [1/2]

const_iterator gtsam::Factor::end ( ) const
inlineinherited

Iterator at end of involved variable keys

◆ end() [2/2]

iterator gtsam::Factor::end ( )
inlineinherited

Iterator at end of involved variable keys

◆ equals()

bool gtsam::LinearContainerFactor::equals ( const NonlinearFactor f,
double  tol = 1e-9 
) const
overridevirtual

Check if two factors are equal

Reimplemented from gtsam::NonlinearFactor.

◆ error() [1/2]

double gtsam::LinearContainerFactor::error ( const Values c) const
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.

Returns
nonlinear error if linearizationPoint present, zero otherwise

Reimplemented from gtsam::NonlinearFactor.

◆ error() [2/2]

double gtsam::NonlinearFactor::error ( const HybridValues c) const
overridevirtualinherited

All factor types need to implement an error function. In factor graphs, this is the negative log-likelihood.

Reimplemented from gtsam::Factor.

◆ FromIterators()

template<typename ITERATOR >
static Factor gtsam::Factor::FromIterators ( ITERATOR  first,
ITERATOR  last 
)
inlinestaticprotectedinherited

Construct factor from iterator keys. This is called internally from derived factor static factor methods, as a workaround for not being able to call the protected constructors above.

◆ FromKeys()

template<typename CONTAINER >
static Factor gtsam::Factor::FromKeys ( const CONTAINER &  keys)
inlinestaticprotectedinherited

Construct factor from container of keys. This is called internally from derived factor static factor methods, as a workaround for not being able to call the protected constructors above.

◆ isJacobian()

bool gtsam::LinearContainerFactor::isJacobian ( ) const

Simple checks whether this is a Jacobian or Hessian factor

◆ keys()

KeyVector& gtsam::Factor::keys ( )
inlineinherited
Returns
keys involved in this factor

◆ linearizationPoint()

const std::optional<Values>& gtsam::LinearContainerFactor::linearizationPoint ( ) const
inline

Extract the linearization point used in recalculating error

◆ linearize()

GaussianFactor::shared_ptr gtsam::LinearContainerFactor::linearize ( const Values c) const
overridevirtual

Linearize to a GaussianFactor, with method depending on the presence of a linearizationPoint

  • With no linearization point, returns a cloned version of the stored linear factor.
  • With a linearization point provided, returns a relinearized version of the linearized factor.

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.

◆ negateToGaussian()

GaussianFactor::shared_ptr gtsam::LinearContainerFactor::negateToGaussian ( ) const

Creates an anti-factor directly

◆ negateToNonlinear()

NonlinearFactor::shared_ptr gtsam::LinearContainerFactor::negateToNonlinear ( ) const

Creates the equivalent anti-factor as another LinearContainerFactor.

◆ print()

void gtsam::LinearContainerFactor::print ( const std::string &  s = "",
const KeyFormatter keyFormatter = gtsam::DefaultKeyFormatter 
) const
overridevirtual

print

Reimplemented from gtsam::Factor.

◆ rekey() [1/2]

NonlinearFactor::shared_ptr gtsam::LinearContainerFactor::rekey ( const std::map< Key, Key > &  rekey_mapping) const
overridevirtual

Creates a shared_ptr clone of the factor with different keys using a map from old->new keys

Reimplemented from gtsam::NonlinearFactor.

◆ rekey() [2/2]

NonlinearFactor::shared_ptr gtsam::LinearContainerFactor::rekey ( const KeyVector new_keys) const
overridevirtual

Clones a factor and fully replaces its keys

Parameters
new_keysis the full replacement set of keys

Reimplemented from gtsam::NonlinearFactor.

◆ sendable()

virtual bool gtsam::NonlinearFactor::sendable ( ) const
inlinevirtualinherited

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)

Reimplemented in gtsam::CustomFactor.

◆ size()

size_t gtsam::Factor::size ( ) const
inlineinherited
Returns
the number of variables involved in this factor

◆ toHessian()

std::shared_ptr<HessianFactor> gtsam::LinearContainerFactor::toHessian ( ) const

Casts to HessianFactor

◆ toJacobian()

std::shared_ptr<JacobianFactor> gtsam::LinearContainerFactor::toJacobian ( ) const

Casts to JacobianFactor


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