|  | 
| gtsam::NonlinearFactor::shared_ptr | clone () const override | 
|  | 
| Vector | evaluateError (const Rot3 &iRc, OptionalMatrixType H) const override | 
|  | vector of errors returns 2D vector  More... 
 | 
|  | 
| void | print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override | 
|  | print  More... 
 | 
|  | 
|  | RotateDirectionsFactor (Key key, const Unit3 &i_p, const Unit3 &c_z, const SharedNoiseModel &model) | 
|  | Constructor.  More... 
 | 
|  | 
| Key | key () 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 | 
|  | 
| 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 | 
|  | 
|  | 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 | 
|  | 
| 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 () | 
|  | 
|  | 
| enum |  | 
|  | N is the number of variables (N-way factor)  More... 
 | 
|  | 
| using | ValueType = typename std::tuple_element< I - 1, std::tuple< ValueTypes... > >::type | 
|  | 
| typedef std::shared_ptr< This > | shared_ptr | 
|  | 
| typedef std::shared_ptr< This > | shared_ptr | 
|  | 
| typedef KeyVector::const_iterator | const_iterator | 
|  | Const iterator over keys.  More... 
 | 
|  | 
| typedef KeyVector::iterator | iterator | 
|  | Iterator over keys.  More... 
 | 
|  | 
| 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 > | 
|  | 
| typedef NonlinearFactor | Base | 
|  | 
| typedef NoiseModelFactor | This | 
|  | 
| typedef Factor | Base | 
|  | 
| typedef NonlinearFactor | This | 
|  | 
|  | NoiseModelFactor (const SharedNoiseModel &noiseModel) | 
|  | 
|  | Factor () | 
|  | 
| template<typename CONTAINER > | 
|  | Factor (const CONTAINER &keys) | 
|  | 
| template<typename ITERATOR > | 
|  | Factor (ITERATOR first, ITERATOR last) | 
|  | 
| template<typename CONTAINER > | 
| static Factor | FromKeys (const CONTAINER &keys) | 
|  | 
| template<typename ITERATOR > | 
| static Factor | FromIterators (ITERATOR first, ITERATOR last) | 
|  | 
| SharedNoiseModel | noiseModel_ | 
|  | 
| KeyVector | keys_ | 
|  | The keys involved in this factor.  More... 
 | 
|  | 
Factor on unknown rotation iRc that relates two directions c Directions provide less constraints than a full rotation 
Definition at line 69 of file RotateFactor.h.