Public Types | Public Member Functions | Protected Types | Protected Member Functions | List of all members
gtsam::NonlinearEquality2< T > Class Template Reference

#include <NonlinearEquality.h>

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

Public Types

typedef std::shared_ptr< NonlinearEquality2< T > > shared_ptr
 
- Public Types inherited from gtsam::NonlinearEqualityConstraint
typedef NonlinearConstraint Base
 
typedef NonlinearFactor Base
 
typedef std::shared_ptr< Thisshared_ptr
 
typedef NonlinearEqualityConstraint This
 
- Public Types inherited from gtsam::NonlinearConstraint
typedef NoiseModelFactor Base
 
typedef NonlinearFactor Base
 
- Public Types inherited from gtsam::NoiseModelFactor
typedef std::shared_ptr< Thisshared_ptr
 
- Public Types inherited from gtsam::NonlinearFactor
typedef std::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...
 

Public Member Functions

gtsam::NonlinearFactor::shared_ptr clone () const override
 
Vector evaluateError (const T &x1, const T &x2, OptionalMatrixType H1=nullptr, OptionalMatrixType H2=nullptr) const
 g(x) with optional derivative2 More...
 
 NonlinearEquality2 (Key key1, Key key2, double mu=1e4)
 
Vector unwhitenedError (const Values &x, OptionalMatrixVecType H=nullptr) const override
 
 ~NonlinearEquality2 () override
 
- Public Member Functions inherited from gtsam::NonlinearEqualityConstraint
virtual ~NonlinearEqualityConstraint ()
 
- Public Member Functions inherited from gtsam::NonlinearConstraint
double error (const HybridValues &c) const override
 
virtual double error (const Values &c) const
 
virtual bool feasible (const Values &x, const double tolerance=1e-5) const
 
virtual NoiseModelFactor::shared_ptr penaltyFactor (const double mu=1.0) const
 
const Vector sigmas () const
 
virtual std::vector< MatrixunwhitenedHessian (const Values &x) const
 
virtual double violation (const Values &x) const
 
virtual ~NonlinearConstraint ()
 
- Public Member Functions inherited from gtsam::NoiseModelFactor
shared_ptr cloneWithNewNoiseModel (const SharedNoiseModel newNoise) const
 
size_t dim () const override
 
bool equals (const NonlinearFactor &f, double tol=1e-9) const override
 
double error (const HybridValues &c) const override
 
virtual double error (const Values &c) const
 
double error (const Values &c) const override
 
std::shared_ptr< GaussianFactorlinearize (const Values &x) const override
 
const SharedNoiseModelnoiseModel () const
 access to the noise model More...
 
 NoiseModelFactor ()
 
template<typename CONTAINER >
 NoiseModelFactor (const SharedNoiseModel &noiseModel, const CONTAINER &keys)
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 
Vector unweightedWhitenedError (const Values &c) const
 
Vector unwhitenedError (const Values &x, std::vector< Matrix > &H) const
 
double weight (const Values &c) const
 
Vector whitenedError (const Values &c) const
 
 ~NoiseModelFactor () override
 
- Public Member Functions inherited from gtsam::NonlinearFactor
 NonlinearFactor ()
 
template<typename CONTAINER >
 NonlinearFactor (const CONTAINER &keys)
 
double error (const HybridValues &c) const override
 
virtual bool active (const Values &) const
 
virtual shared_ptr rekey (const std::map< Key, Key > &rekey_mapping) const
 
virtual shared_ptr rekey (const KeyVector &new_keys) const
 
virtual bool sendable () const
 
- Public Member Functions inherited from gtsam::Factor
virtual ~Factor ()=default
 Default destructor. More...
 
bool empty () const
 Whether the factor is empty (involves zero variables). 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...
 
bool equals (const This &other, double tol=1e-9) const
 check equality More...
 
KeyVectorkeys ()
 
iterator begin ()
 
iterator end ()
 

Protected Types

typedef NonlinearEqualityConstraint Base
 
typedef NonlinearEquality2< TThis
 
- Protected Types inherited from gtsam::NoiseModelFactor
typedef NonlinearFactor Base
 
typedef NoiseModelFactor This
 
- Protected Types inherited from gtsam::NonlinearFactor
typedef Factor Base
 
typedef NonlinearFactor This
 

Protected Member Functions

 NonlinearEquality2 ()
 Default constructor to allow for serialization. More...
 
- Protected Member Functions inherited from gtsam::NonlinearConstraint
SharedDiagonal penaltyNoise (const double mu) const
 
- Protected Member Functions inherited from gtsam::NoiseModelFactor
 NoiseModelFactor (const SharedNoiseModel &noiseModel)
 
- Protected Member Functions inherited from gtsam::Factor
 Factor ()
 
template<typename CONTAINER >
 Factor (const CONTAINER &keys)
 
template<typename ITERATOR >
 Factor (ITERATOR first, ITERATOR last)
 

Additional Inherited Members

- Static Protected Member Functions inherited from gtsam::NonlinearConstraint
static SharedNoiseModel constrainedNoise (const Vector &sigmas)
 
- 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::NoiseModelFactor
SharedNoiseModel noiseModel_
 
- Protected Attributes inherited from gtsam::Factor
KeyVector keys_
 The keys involved in this factor. More...
 

Detailed Description

template<class T>
class gtsam::NonlinearEquality2< T >

Simple binary equality constraint - this constraint forces two variables to be the same.

Definition at line 320 of file NonlinearEquality.h.

Member Typedef Documentation

◆ Base

template<class T >
typedef NonlinearEqualityConstraint gtsam::NonlinearEquality2< T >::Base
protected

Definition at line 322 of file NonlinearEquality.h.

◆ shared_ptr

template<class T >
typedef std::shared_ptr<NonlinearEquality2<T> > gtsam::NonlinearEquality2< T >::shared_ptr

Definition at line 331 of file NonlinearEquality.h.

◆ This

template<class T >
typedef NonlinearEquality2<T> gtsam::NonlinearEquality2< T >::This
protected

Definition at line 323 of file NonlinearEquality.h.

Constructor & Destructor Documentation

◆ NonlinearEquality2() [1/2]

template<class T >
gtsam::NonlinearEquality2< T >::NonlinearEquality2 ( )
inlineprotected

Default constructor to allow for serialization.

Definition at line 328 of file NonlinearEquality.h.

◆ NonlinearEquality2() [2/2]

template<class T >
gtsam::NonlinearEquality2< T >::NonlinearEquality2 ( Key  key1,
Key  key2,
double  mu = 1e4 
)
inline

Constructor

Parameters
key1the key for the first unknown variable to be constrained
key2the key for the second unknown variable to be constrained
mua parameter which really turns this into a strong prior

Definition at line 340 of file NonlinearEquality.h.

◆ ~NonlinearEquality2()

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

Definition at line 343 of file NonlinearEquality.h.

Member Function Documentation

◆ clone()

template<class T >
gtsam::NonlinearFactor::shared_ptr gtsam::NonlinearEquality2< T >::clone ( ) const
inlineoverridevirtual
Returns
a deep copy of this factor

Reimplemented from gtsam::NonlinearFactor.

Definition at line 346 of file NonlinearEquality.h.

◆ evaluateError()

template<class T >
Vector gtsam::NonlinearEquality2< T >::evaluateError ( const T x1,
const T x2,
OptionalMatrixType  H1 = nullptr,
OptionalMatrixType  H2 = nullptr 
) const
inline

g(x) with optional derivative2

Definition at line 352 of file NonlinearEquality.h.

◆ unwhitenedError()

template<class T >
Vector gtsam::NonlinearEquality2< T >::unwhitenedError ( const Values x,
OptionalMatrixVecType  H = nullptr 
) const
inlineoverridevirtual

Error function without the NoiseModel, $ z-h(x) $. Override this method to finish implementing an N-way factor. If the optional arguments is specified, it should compute both the function evaluation and its derivative(s) in H.

Implements gtsam::NoiseModelFactor.

Definition at line 360 of file NonlinearEquality.h.


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


gtsam
Author(s):
autogenerated on Wed Jan 22 2025 04:15:09