gtsam 4.2
gtsam
Loading...
Searching...
No Matches
gtsam::EssentialMatrixConstraint Class Reference

Detailed Description

Binary factor between two Pose3 variables induced by an EssentialMatrix measurement.

Inheritance diagram for gtsam::EssentialMatrixConstraint:

Public Member Functions

 EssentialMatrixConstraint ()
 default constructor - only use for serialization
 EssentialMatrixConstraint (Key key1, Key key2, const EssentialMatrix &measuredE, const SharedNoiseModel &model)
 Constructor.
gtsam::NonlinearFactor::shared_ptr clone () const override
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 implement functions needed for Testable
bool equals (const NonlinearFactor &expected, double tol=1e-9) const override
 equals
Vector evaluateError (const Pose3 &p1, const Pose3 &p2, boost::optional< Matrix & > Hp1=boost::none, boost::optional< Matrix & > Hp2=boost::none) const override
 implement functions needed to derive from Factor
const EssentialMatrixmeasured () const
 return the measured
Public Member Functions inherited from gtsam::NoiseModelFactorN< Pose3, Pose3 >
Key key () const
 Returns a key.
 NoiseModelFactorN ()
 Default Constructor for I/O.
 NoiseModelFactorN (const SharedNoiseModel &noiseModel, KeyType< ValueTypes >... keys)
 Constructor.
 NoiseModelFactorN (const SharedNoiseModel &noiseModel, CONTAINER keys)
 Constructor.
Vector unwhitenedError (const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override
 This implements the unwhitenedError virtual function by calling the n-key specific version of evaluateError, which is pure virtual so must be implemented in the derived class.
virtual Vector evaluateError (const ValueTypes &... x, OptionalMatrix< ValueTypes >... H) const=0
 Override evaluateError to finish implementing an n-way factor.
Vector evaluateError (const ValueTypes &... x) const
 No-Jacobians requested function overload.
Vector evaluateError (const ValueTypes &... x, OptionalJacArgs &&... H) const
 Some (but not all) optional Jacobians are omitted (function overload).
Key key1 () const
Key key2 () const
Key key3 () const
Key key4 () const
Key key5 () const
Key key6 () const
Public Member Functions inherited from gtsam::NoiseModelFactor
 NoiseModelFactor ()
 Default constructor for I/O only.
 ~NoiseModelFactor () override
 Destructor.
template<typename CONTAINER>
 NoiseModelFactor (const SharedNoiseModel &noiseModel, const CONTAINER &keys)
 Constructor.
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 Print.
bool equals (const NonlinearFactor &f, double tol=1e-9) const override
 Check if two factors are equal.
size_t dim () const override
 get the dimension of the factor (number of rows on linearization)
const SharedNoiseModelnoiseModel () const
 access to the noise model
Vector whitenedError (const Values &c) const
 Vector of errors, whitened This is the raw error, i.e., i.e.
Vector unweightedWhitenedError (const Values &c) const
 Vector of errors, whitened, but unweighted by any loss function.
double weight (const Values &c) const
 Compute the effective weight of the factor from the noise model.
double error (const Values &c) const override
 Calculate the error of the factor.
boost::shared_ptr< GaussianFactor > linearize (const Values &x) const override
 Linearize a non-linearFactorN to get a GaussianFactor, \( Ax-b \approx h(x+\delta x)-z = h(x) + A \delta x - z \) Hence \( b = z - h(x) = - \mathtt{error\_vector}(x) \).
shared_ptr cloneWithNewNoiseModel (const SharedNoiseModel newNoise) const
 Creates a shared_ptr clone of the factor with a new noise model.
 NonlinearFactor ()
 Default constructor for I/O only.
template<typename CONTAINER>
 NonlinearFactor (const CONTAINER &keys)
 Constructor from a collection of the keys involved in this factor.
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 print
virtual ~NonlinearFactor ()
 Destructor.
double error (const HybridValues &c) const override
 All factor types need to implement an error function.
virtual bool active (const Values &) const
 Checks whether a factor should be used based on a set of values.
virtual shared_ptr rekey (const std::map< Key, Key > &rekey_mapping) const
 Creates a shared_ptr clone of the factor with different keys using a map from old->new keys.
virtual shared_ptr rekey (const KeyVector &new_keys) const
 Clones a factor and fully replaces its keys.
virtual bool sendable () const
 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).
Public Member Functions inherited from gtsam::Factor
virtual ~Factor ()=default
 Default destructor.
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
 Iterator at beginning of involved variable keys.
const_iterator end () const
 Iterator at end of involved variable keys.
size_t size () const
virtual void printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print only keys
bool equals (const This &other, double tol=1e-9) const
 check equality
KeyVectorkeys ()
iterator begin ()
 Iterator at beginning of involved variable keys.
iterator end ()
 Iterator at end of involved variable keys.

Public Types

typedef boost::shared_ptr< EssentialMatrixConstraintshared_ptr
 The measurement is an essential matrix.
Public Types inherited from gtsam::NoiseModelFactorN< Pose3, Pose3 >
enum  
 N is the number of variables (N-way factor).
using ValueType
 The type of the I'th template param can be obtained as ValueType.
Public Types inherited from gtsam::NoiseModelFactor
typedef boost::shared_ptr< This > shared_ptr
 Noise model.
Public Types inherited from gtsam::NonlinearFactor
typedef boost::shared_ptr< This > shared_ptr
Public Types inherited from gtsam::Factor
typedef KeyVector::iterator iterator
 Iterator over keys.
typedef KeyVector::const_iterator const_iterator
 Const iterator over keys.

Friends

class boost::serialization::access
 Serialization function.

Additional Inherited Members

Protected Types inherited from gtsam::NoiseModelFactorN< Pose3, Pose3 >
using Base
using This
using OptionalMatrix
using KeyType
using IsConvertible
using IndexIsValid
using ContainerElementType
using IsContainerOfKeys
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 inherited from gtsam::NoiseModelFactor
 NoiseModelFactor (const SharedNoiseModel &noiseModel)
 Constructor - only for subclasses, as this does not set keys.
 Factor ()
 Default constructor for I/O.
template<typename CONTAINER>
 Factor (const CONTAINER &keys)
 Construct factor from container of keys.
template<typename ITERATOR>
 Factor (ITERATOR first, ITERATOR last)
 Construct factor from iterator keys.
template<typename CONTAINER>
static Factor FromKeys (const CONTAINER &keys)
 Construct factor from container of keys.
template<typename ITERATOR>
static Factor FromIterators (ITERATOR first, ITERATOR last)
 Construct factor from iterator keys.
Protected Attributes inherited from gtsam::NoiseModelFactor
SharedNoiseModel noiseModel_
Protected Attributes inherited from gtsam::Factor
KeyVector keys_
 The keys involved in this factor.

Constructor & Destructor Documentation

◆ EssentialMatrixConstraint()

gtsam::EssentialMatrixConstraint::EssentialMatrixConstraint ( Key key1,
Key key2,
const EssentialMatrix & measuredE,
const SharedNoiseModel & model )
inline

Constructor.

Parameters
key1key for first pose
key2key for second pose
measuredEmeasured EssentialMatrix
modelnoise model, 5D !

Member Function Documentation

◆ clone()

gtsam::NonlinearFactor::shared_ptr gtsam::EssentialMatrixConstraint::clone ( ) const
inlineoverridevirtual
Returns
a deep copy of this factor

Reimplemented from gtsam::NonlinearFactor.

◆ equals()

bool gtsam::EssentialMatrixConstraint::equals ( const NonlinearFactor & expected,
double tol = 1e-9 ) const
overridevirtual

equals

Reimplemented from gtsam::NonlinearFactor.

◆ evaluateError()

Vector gtsam::EssentialMatrixConstraint::evaluateError ( const Pose3 & p1,
const Pose3 & p2,
boost::optional< Matrix & > Hp1 = boost::none,
boost::optional< Matrix & > Hp2 = boost::none ) const
override

implement functions needed to derive from Factor

vector of errors

◆ print()

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

implement functions needed for Testable

print

Reimplemented from gtsam::Factor.


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