Public Member Functions | Private Types | Private Attributes | List of all members
gtsam::RangeFactorWithTransform< A1, A2, T > Class Template Reference

#include <RangeFactor.h>

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

Public Member Functions

gtsam::NonlinearFactor::shared_ptr clone () const override
 
Vector evaluateError (const A1 &a1, const A2 &a2, Matrix &H1, Matrix &H2) const
 
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 &keyFormatter=DefaultKeyFormatter) const override
 
 RangeFactorWithTransform ()
 
 RangeFactorWithTransform (Key key1, Key key2, T measured, const SharedNoiseModel &model, const A1 &body_T_sensor)
 
 ~RangeFactorWithTransform () override
 
- Public Member Functions inherited from gtsam::ExpressionFactorN< typename Range< A1, A1 >::result_type, A1, A1 >
virtual Expression< typename Range< A1, A1 >::result_type > expression (const ArrayNKeys &keys) const
 
- Public Member Functions inherited from gtsam::ExpressionFactor< typename Range< A1, A1 >::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 Range< A1, A1 >::result_type &measurement, const Expression< typename Range< A1, A1 >::result_type > &expression)
 
std::shared_ptr< GaussianFactorlinearize (const Values &x) const override
 
const typename Range< A1, A1 >::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...
 

Private Types

typedef ExpressionFactorN< T, A1, A2Base
 
typedef RangeFactorWithTransform< A1, A2This
 

Private Attributes

A1 body_T_sensor_
 The pose of the sensor in the body frame. More...
 

Additional Inherited Members

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

Detailed Description

template<typename A1, typename A2 = A1, typename T = typename Range<A1, A2>::result_type>
class gtsam::RangeFactorWithTransform< A1, A2, T >

Binary factor for a range measurement, with a transform applied

Definition at line 104 of file sam/RangeFactor.h.

Member Typedef Documentation

◆ Base

template<typename A1 , typename A2 = A1, typename T = typename Range<A1, A2>::result_type>
typedef ExpressionFactorN<T, A1, A2> gtsam::RangeFactorWithTransform< A1, A2, T >::Base
private

Definition at line 107 of file sam/RangeFactor.h.

◆ This

template<typename A1 , typename A2 = A1, typename T = typename Range<A1, A2>::result_type>
typedef RangeFactorWithTransform<A1, A2> gtsam::RangeFactorWithTransform< A1, A2, T >::This
private

Definition at line 106 of file sam/RangeFactor.h.

Constructor & Destructor Documentation

◆ RangeFactorWithTransform() [1/2]

template<typename A1 , typename A2 = A1, typename T = typename Range<A1, A2>::result_type>
gtsam::RangeFactorWithTransform< A1, A2, T >::RangeFactorWithTransform ( )
inline

Definition at line 113 of file sam/RangeFactor.h.

◆ RangeFactorWithTransform() [2/2]

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

Definition at line 115 of file sam/RangeFactor.h.

◆ ~RangeFactorWithTransform()

template<typename A1 , typename A2 = A1, typename T = typename Range<A1, A2>::result_type>
gtsam::RangeFactorWithTransform< A1, A2, T >::~RangeFactorWithTransform ( )
inlineoverride

Definition at line 122 of file sam/RangeFactor.h.

Member Function Documentation

◆ clone()

template<typename A1 , typename A2 = A1, typename T = typename Range<A1, A2>::result_type>
gtsam::NonlinearFactor::shared_ptr gtsam::RangeFactorWithTransform< A1, A2, T >::clone ( ) const
inlineoverride
Returns
a deep copy of this factor

Definition at line 125 of file sam/RangeFactor.h.

◆ evaluateError() [1/2]

template<typename A1 , typename A2 = A1, typename T = typename Range<A1, A2>::result_type>
Vector gtsam::RangeFactorWithTransform< A1, A2, T >::evaluateError ( const A1 a1,
const A2 a2,
Matrix H1,
Matrix H2 
) const
inline

Definition at line 154 of file sam/RangeFactor.h.

◆ evaluateError() [2/2]

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

Definition at line 140 of file sam/RangeFactor.h.

◆ expression()

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

Definition at line 131 of file sam/RangeFactor.h.

◆ print()

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

print contents

Definition at line 159 of file sam/RangeFactor.h.

Member Data Documentation

◆ body_T_sensor_

template<typename A1 , typename A2 = A1, typename T = typename Range<A1, A2>::result_type>
A1 gtsam::RangeFactorWithTransform< A1, A2, T >::body_T_sensor_
private

The pose of the sensor in the body frame.

Definition at line 109 of file sam/RangeFactor.h.


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


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