#include <ReferenceFrameFactor.h>
Public Types | |
typedef NoiseModelFactorN< POINT, TRANSFORM, POINT > | Base |
typedef POINT | Point |
typedef ReferenceFrameFactor< POINT, TRANSFORM > | This |
typedef TRANSFORM | Transform |
Public Types inherited from gtsam::NoiseModelFactorN< POINT, TRANSFORM, POINT > | |
enum | |
N is the number of variables (N-way factor) More... | |
using | ValueType = typename std::tuple_element< I - 1, std::tuple< ValueTypes... > >::type |
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 | |
NonlinearFactor::shared_ptr | clone () const override |
Vector | evaluateError (const Point &global, const Transform &trans, const Point &local, OptionalMatrixType Dforeign, OptionalMatrixType Dtrans, OptionalMatrixType Dlocal) const override |
Key | global_key () const |
Key | local_key () const |
void | print (const std::string &s="", const gtsam::KeyFormatter &keyFormatter=DefaultKeyFormatter) const override |
ReferenceFrameFactor (double mu, Key globalKey, Key transKey, Key localKey) | |
ReferenceFrameFactor (Key globalKey, Key transKey, Key localKey, const noiseModel::Base::shared_ptr &model) | |
ReferenceFrameFactor (Key globalKey, Key transKey, Key localKey, double sigma=1e-2) | |
Key | transform_key () const |
~ReferenceFrameFactor () override | |
Public Member Functions inherited from gtsam::NoiseModelFactorN< POINT, TRANSFORM, POINT > | |
Key | key () const |
virtual Vector | unwhitenedError (const Values &x, OptionalMatrixVecType H=nullptr) const =0 |
Vector | unwhitenedError (const Values &x, std::vector< Matrix > &H) const |
~NoiseModelFactorN () override | |
NoiseModelFactorN () | |
Default Constructor for I/O. More... | |
NoiseModelFactorN (const SharedNoiseModel &noiseModel, KeyType< ValueTypes >... keys) | |
NoiseModelFactorN (const SharedNoiseModel &noiseModel, CONTAINER keys) | |
Vector | unwhitenedError (const Values &x, OptionalMatrixVecType H=nullptr) const override |
virtual Vector | evaluateError (const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0 |
Vector | evaluateError (const ValueTypes &... x, MatrixTypeT< ValueTypes > &... H) const |
Vector | evaluateError (const ValueTypes &... x) const |
AreAllMatrixRefs< Vector, OptionalJacArgs... > | evaluateError (const ValueTypes &... x, OptionalJacArgs &&... H) const |
AreAllMatrixPtrs< Vector, OptionalJacArgs... > | evaluateError (const ValueTypes &... x, OptionalJacArgs &&... H) const |
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 | |
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 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) | |
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 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 | |
ReferenceFrameFactor () | |
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 | |
Protected Types inherited from gtsam::NoiseModelFactorN< POINT, TRANSFORM, POINT > | |
using | Base = NoiseModelFactor |
using | KeyType = Key |
using | MatrixTypeT = Matrix |
using | OptionalMatrixTypeT = Matrix * |
using | This = NoiseModelFactorN< ValueTypes... > |
using | IsConvertible = typename std::enable_if< std::is_convertible< From, To >::value, void >::type |
using | IndexIsValid = typename std::enable_if<(I >=1) &&(I<=N), void >::type |
using | ContainerElementType = typename std::decay< decltype(*std::declval< Container >().begin())>::type |
using | IsContainerOfKeys = IsConvertible< ContainerElementType< Container >, Key > |
using | AreAllMatrixRefs = std::enable_if_t<(... &&std::is_convertible< Args, Matrix & >::value), Ret > |
using | IsMatrixPointer = std::is_same< typename std::decay_t< Arg >, Matrix * > |
using | IsNullpointer = std::is_same< typename std::decay_t< Arg >, std::nullptr_t > |
using | AreAllMatrixPtrs = std::enable_if_t<(... &&(IsMatrixPointer< Args >::value||IsNullpointer< Args >::value)), Ret > |
Protected Types inherited from gtsam::NoiseModelFactor | |
typedef NonlinearFactor | Base |
typedef NoiseModelFactor | This |
Protected Types inherited from gtsam::NonlinearFactor | |
typedef Factor | Base |
typedef NonlinearFactor | This |
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... | |
A constraint between two landmarks in separate maps Templated on: Point : Type of landmark Transform : Transform variable class
The transform is defined as transforming global to local: l = lTg * g
The Point and Transform concepts must be Lie types, and the transform relationship "Point = transformFrom(Transform, Point)" must exist.
To implement this function in new domains, specialize a new version of Point transform_point<Transform,Point>(transform, global, Dtrans, Dglobal) to use the correct point and transform types.
This base class should be specialized to implement the cost function for specific classes of landmarks
Definition at line 57 of file ReferenceFrameFactor.h.
typedef NoiseModelFactorN<POINT, TRANSFORM, POINT> gtsam::ReferenceFrameFactor< POINT, TRANSFORM >::Base |
Definition at line 63 of file ReferenceFrameFactor.h.
typedef POINT gtsam::ReferenceFrameFactor< POINT, TRANSFORM >::Point |
Definition at line 69 of file ReferenceFrameFactor.h.
typedef ReferenceFrameFactor<POINT, TRANSFORM> gtsam::ReferenceFrameFactor< POINT, TRANSFORM >::This |
Definition at line 64 of file ReferenceFrameFactor.h.
typedef TRANSFORM gtsam::ReferenceFrameFactor< POINT, TRANSFORM >::Transform |
Definition at line 70 of file ReferenceFrameFactor.h.
|
inlineprotected |
default constructor for serialization only
Definition at line 60 of file ReferenceFrameFactor.h.
|
inline |
General constructor with arbitrary noise model (constrained or otherwise)
Definition at line 75 of file ReferenceFrameFactor.h.
|
inline |
Construct a hard frame of reference reference constraint with equal mu values for each degree of freedom.
Definition at line 82 of file ReferenceFrameFactor.h.
|
inline |
Simple soft constraint constructor for frame of reference, with equal weighting for each degree of freedom.
Definition at line 89 of file ReferenceFrameFactor.h.
|
inlineoverride |
Definition at line 93 of file ReferenceFrameFactor.h.
|
inlineoverridevirtual |
Creates a shared_ptr clone of the factor - needs to be specialized to allow for subclasses
By default, throws exception if subclass does not implement the function.
Reimplemented from gtsam::NonlinearFactor.
Definition at line 95 of file ReferenceFrameFactor.h.
|
inlineoverride |
Combined cost and derivative function using boost::optional
Definition at line 100 of file ReferenceFrameFactor.h.
|
inline |
Definition at line 120 of file ReferenceFrameFactor.h.
|
inline |
Definition at line 122 of file ReferenceFrameFactor.h.
|
inlineoverridevirtual |
Reimplemented from gtsam::NoiseModelFactor.
Definition at line 110 of file ReferenceFrameFactor.h.
|
inline |
Definition at line 121 of file ReferenceFrameFactor.h.