#include <NonlinearConstraint.h>

Public Types | |
| typedef NoiseModelFactor | Base |
| typedef NonlinearFactor | Base |
Public Types inherited from gtsam::NoiseModelFactor | |
| typedef std::shared_ptr< This > | shared_ptr |
Public Types inherited from gtsam::NonlinearFactor | |
| typedef std::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 | |
| 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< Matrix > | unwhitenedHessian (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< GaussianFactor > | linearize (const Values &x) const override |
| const SharedNoiseModel & | noiseModel () 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 |
| virtual Vector | unwhitenedError (const Values &x, OptionalMatrixVecType H=nullptr) const =0 |
| 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 &c) const |
| virtual shared_ptr | clone () 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 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... | |
| bool | equals (const This &other, double tol=1e-9) const |
| check equality More... | |
| KeyVector & | keys () |
| iterator | begin () |
| iterator | end () |
Protected Member Functions | |
| 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) | |
Static Protected Member Functions | |
| 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) |
Additional Inherited Members | |
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 Attributes inherited from gtsam::NoiseModelFactor | |
| SharedNoiseModel | noiseModel_ |
Protected Attributes inherited from gtsam::Factor | |
| KeyVector | keys_ |
| The keys involved in this factor. More... | |
Base class for nonlinear constraint. The constraint is represented as a NoiseModelFactor with Constrained noise model. whitenedError() returns The constraint violation vector. unwhitenedError() returns the sigma-scaled constraint violation vector.
Definition at line 36 of file NonlinearConstraint.h.
Definition at line 38 of file NonlinearConstraint.h.
Use constructors of NoiseModelFactor.
Definition at line 203 of file NonlinearFactor.h.
|
inlinevirtual |
Destructor.
Definition at line 46 of file NonlinearConstraint.h.
|
inlinestaticprotected |
Default constrained noisemodel used for construction of constraint.
Definition at line 75 of file NonlinearConstraint.h.
|
override |
Definition at line 32 of file NonlinearFactor.cpp.
| double NonlinearFactor::error |
Definition at line 27 of file NonlinearFactor.cpp.
|
inlinevirtual |
Check if constraint violation is within tolerance.
Definition at line 57 of file NonlinearConstraint.h.
|
inlinevirtual |
Create a cost factor representing the L2 penalty function with scaling coefficient mu.
Reimplemented in gtsam::ZeroCostConstraint, gtsam::ScalarExpressionInequalityConstraint, and gtsam::ExpressionEqualityConstraint< T >.
Definition at line 49 of file NonlinearConstraint.h.
|
inlineprotected |
Noise model used for the penalty function.
Definition at line 70 of file NonlinearConstraint.h.
|
inline |
Definition at line 61 of file NonlinearConstraint.h.
|
inlinevirtual |
Definition at line 64 of file NonlinearConstraint.h.
|
inlinevirtual |
Return the norm of the constraint violation vector.
Definition at line 54 of file NonlinearConstraint.h.