Public Types | Public Member Functions | List of all members
gtsam::BearingFactor< A1, A2, T > Struct Template Reference

#include <BearingFactor.h>

Inheritance diagram for gtsam::BearingFactor< A1, A2, T >:
Inheritance graph
[legend]

Public Types

typedef ExpressionFactorN< T, A1, A2Base
 
- Public Types inherited from gtsam::ExpressionFactorN< typename Bearing< A1, A2 >::result_type, A1, A2 >
using ArrayNKeys = std::array< Key, NARY_EXPRESSION_SIZE >
 
- Public Types inherited from gtsam::ExpressionFactor< typename Bearing< A1, A2 >::result_type >
typedef std::shared_ptr< ExpressionFactor< typename Bearing< A1, A2 >::result_type > > shared_ptr
 

Public Member Functions

 BearingFactor ()
 default constructor More...
 
 BearingFactor (Key key1, Key key2, const T &measured, const SharedNoiseModel &model)
 primary constructor More...
 
Vector evaluateError (const A1 &a1, const A2 &a2, OptionalMatrixType H1=OptionalNone, OptionalMatrixType H2=OptionalNone) const
 
Expression< Texpression (const typename Base::ArrayNKeys &keys) const override
 
void print (const std::string &s="", const KeyFormatter &kf=DefaultKeyFormatter) const override
 print More...
 
- Public Member Functions inherited from gtsam::ExpressionFactorN< typename Bearing< A1, A2 >::result_type, A1, A2 >
virtual Expression< typename Bearing< A1, A2 >::result_type > expression (const ArrayNKeys &keys) const
 
- Public Member Functions inherited from gtsam::ExpressionFactor< typename Bearing< A1, A2 >::result_type >
gtsam::NonlinearFactor::shared_ptr clone () const override
 
bool equals (const NonlinearFactor &f, double tol) const override
 equals relies on Testable traits being defined for T More...
 
 ExpressionFactor (const SharedNoiseModel &noiseModel, const typename Bearing< A1, A2 >::result_type &measurement, const Expression< typename Bearing< A1, A2 >::result_type > &expression)
 
std::shared_ptr< GaussianFactorlinearize (const Values &x) const override
 
const typename Bearing< A1, A2 >::result_type & measured () const
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 print relies on Testable traits being defined for T More...
 
virtual Vector unwhitenedError (const Values &x, OptionalMatrixVecType H=nullptr) const =0
 
Vector unwhitenedError (const Values &x, OptionalMatrixVecType H=nullptr) const override
 
Vector unwhitenedError (const Values &x, std::vector< Matrix > &H) const
 
 ~ExpressionFactor () override
 Destructor. More...
 

Additional Inherited Members

- Static Public Attributes inherited from gtsam::ExpressionFactorN< typename Bearing< A1, A2 >::result_type, A1, A2 >
static const std::size_t NARY_EXPRESSION_SIZE
 
- Protected Types inherited from gtsam::ExpressionFactor< typename Bearing< A1, A2 >::result_type >
typedef ExpressionFactor< typename Bearing< A1, A2 >::result_type > This
 
- Protected Member Functions inherited from gtsam::ExpressionFactorN< typename Bearing< A1, A2 >::result_type, A1, A2 >
 ExpressionFactorN ()=default
 Default constructor, for serialization. More...
 
 ExpressionFactorN (const ArrayNKeys &keys, const SharedNoiseModel &noiseModel, const typename Bearing< A1, A2 >::result_type &measurement)
 Constructor takes care of keys, but still need to call initialize. More...
 
- Protected Member Functions inherited from gtsam::ExpressionFactor< typename Bearing< A1, A2 >::result_type >
 ExpressionFactor ()
 
 ExpressionFactor (const SharedNoiseModel &noiseModel, const typename Bearing< A1, A2 >::result_type &measurement)
 Default constructor, for serialization. More...
 
void initialize (const Expression< typename Bearing< A1, A2 >::result_type > &expression)
 Initialize with constructor arguments. More...
 
- Protected Attributes inherited from gtsam::ExpressionFactor< typename Bearing< A1, A2 >::result_type >
FastVector< intdims_
 dimensions of the Jacobian matrices More...
 
Expression< typename Bearing< A1, A2 >::result_type > expression_
 the expression that is AD enabled More...
 
typename Bearing< A1, A2 >::result_type measured_
 the measurement to be compared with the expression More...
 
- Static Protected Attributes inherited from gtsam::ExpressionFactor< typename Bearing< A1, A2 >::result_type >
static const int Dim
 

Detailed Description

template<typename A1, typename A2, typename T = typename Bearing<A1, A2>::result_type>
struct gtsam::BearingFactor< A1, A2, T >

Binary factor for a bearing measurement Works for any two types A1,A2 for which the functor Bearing<A1,A2>() is defined

Definition at line 37 of file sam/BearingFactor.h.

Member Typedef Documentation

◆ Base

template<typename A1 , typename A2 , typename T = typename Bearing<A1, A2>::result_type>
typedef ExpressionFactorN<T, A1, A2> gtsam::BearingFactor< A1, A2, T >::Base

Definition at line 38 of file sam/BearingFactor.h.

Constructor & Destructor Documentation

◆ BearingFactor() [1/2]

template<typename A1 , typename A2 , typename T = typename Bearing<A1, A2>::result_type>
gtsam::BearingFactor< A1, A2, T >::BearingFactor ( )
inline

default constructor

Definition at line 41 of file sam/BearingFactor.h.

◆ BearingFactor() [2/2]

template<typename A1 , typename A2 , typename T = typename Bearing<A1, A2>::result_type>
gtsam::BearingFactor< A1, A2, T >::BearingFactor ( Key  key1,
Key  key2,
const T measured,
const SharedNoiseModel model 
)
inline

primary constructor

Definition at line 44 of file sam/BearingFactor.h.

Member Function Documentation

◆ evaluateError()

template<typename A1 , typename A2 , typename T = typename Bearing<A1, A2>::result_type>
Vector gtsam::BearingFactor< A1, A2, T >::evaluateError ( const A1 a1,
const A2 a2,
OptionalMatrixType  H1 = OptionalNone,
OptionalMatrixType  H2 = OptionalNone 
) const
inline

Definition at line 64 of file sam/BearingFactor.h.

◆ expression()

template<typename A1 , typename A2 , typename T = typename Bearing<A1, A2>::result_type>
Expression<T> gtsam::BearingFactor< A1, A2, T >::expression ( const typename Base::ArrayNKeys keys) const
inlineoverride

Definition at line 51 of file sam/BearingFactor.h.

◆ print()

template<typename A1 , typename A2 , typename T = typename Bearing<A1, A2>::result_type>
void gtsam::BearingFactor< A1, A2, T >::print ( const std::string &  s = "",
const KeyFormatter kf = DefaultKeyFormatter 
) const
inlineoverride

print

Definition at line 58 of file sam/BearingFactor.h.


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


gtsam
Author(s):
autogenerated on Thu Jun 13 2024 03:16:53