|
| template<int I = 1> |
| 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) |
| |
| template<typename CONTAINER = std::initializer_list<Key>, typename = IsContainerOfKeys<CONTAINER>> |
| | 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 |
| |
| template<typename... OptionalJacArgs, typename = IndexIsValid<sizeof...(OptionalJacArgs) + 1>> |
| AreAllMatrixRefs< Vector, OptionalJacArgs... > | evaluateError (const ValueTypes &... x, OptionalJacArgs &&... H) const |
| |
| template<typename... OptionalJacArgs, typename = IndexIsValid<sizeof...(OptionalJacArgs) + 1>> |
| AreAllMatrixPtrs< Vector, OptionalJacArgs... > | evaluateError (const ValueTypes &... x, OptionalJacArgs &&... H) const |
| |
|
| Key | key1 () const |
| |
| template<int I = 2> |
| Key | key2 () const |
| |
| template<int I = 3> |
| Key | key3 () const |
| |
| template<int I = 4> |
| Key | key4 () const |
| |
| template<int I = 5> |
| Key | key5 () const |
| |
| template<int I = 6> |
| 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 HybridValues &c) const override |
| |
| virtual double | error (const Values &c) const |
| |
| 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) |
| |
| void | print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override |
| |
| 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 &c) const |
| |
| virtual shared_ptr | clone () 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 () |
| |
|
| using | Base = NoiseModelFactor |
| |
| template<typename T > |
| using | KeyType = Key |
| |
| template<typename T = void> |
| using | MatrixTypeT = Matrix |
| |
| template<typename T = void> |
| using | OptionalMatrixTypeT = Matrix * |
| |
| using | This = NoiseModelFactorN< ValueTypes... > |
| |
|
| template<typename From , typename To > |
| using | IsConvertible = typename std::enable_if< std::is_convertible< From, To >::value, void >::type |
| |
| template<int I> |
| using | IndexIsValid = typename std::enable_if<(I >=1) &&(I<=N), void >::type |
| |
| template<typename Container > |
| using | ContainerElementType = typename std::decay< decltype(*std::declval< Container >().begin())>::type |
| |
| template<typename Container > |
| using | IsContainerOfKeys = IsConvertible< ContainerElementType< Container >, Key > |
| |
| template<typename Ret , typename ... Args> |
| using | AreAllMatrixRefs = std::enable_if_t<(... &&std::is_convertible< Args, Matrix & >::value), Ret > |
| |
| template<typename Arg > |
| using | IsMatrixPointer = std::is_same< typename std::decay_t< Arg >, Matrix * > |
| |
| template<typename Arg > |
| using | IsNullpointer = std::is_same< typename std::decay_t< Arg >, std::nullptr_t > |
| |
| template<typename Ret , typename ... Args> |
| 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 |
| |
template<class... ValueTypes>
class gtsam::NoiseModelFactorN< ValueTypes >
A convenient base class for creating your own NoiseModelFactor with n variables. To derive from this class, implement evaluateError().
For example, a 2-way factor that computes the difference in x-translation between a Pose3 and Point3 could be implemented like so:
public:
using Base = NoiseModelFactorN<Pose3, Point3>;
Matrix36 t_H_T;
Point3 t =
T.translation(H_T ? &t_H_T : 0);
if (H_T) *H_T = (
Matrix(1, 6) << t_H_T.row(0)).finished();
if (H_p) *H_p = (
Matrix(1, 3) << -1., 0., 0.).finished();
}
};
}
These factors are templated on a values structure type. The values structures are typically more general than just vectors, e.g., Rot3 or Pose3, which are objects in non-linear manifolds (Lie groups).
Definition at line 434 of file NonlinearFactor.h.
template<class... ValueTypes>
template<int I, typename = IndexIsValid<I>>
The type of the I'th template param can be obtained as ValueType. I is 1-indexed for backwards compatibility/consistency! So for example,
using Factor = NoiseModelFactorN<Pose3, Point3>;
Factor::ValueType<1>
Factor::ValueType<2>
You can also use the shortcuts X1, ..., X6 which are the same as ValueType<1>, ..., ValueType<6> respectively (see detail::NoiseModelFactorAliases).
Note that, if your class is templated AND you want to use ValueType<1> inside your class, due to dependent types you need the template keyword: typename MyFactor<T>::template ValueType<1>.
Definition at line 528 of file NonlinearFactor.h.
template<class... ValueTypes>
template<typename CONTAINER = std::initializer_list<Key>, typename = IsContainerOfKeys<CONTAINER>>
Constructor. Example usage: NoiseModelFactorN(noise, {key1, key2, ..., keyN}) Example usage: NoiseModelFactorN(noise, keys) where keys is a vector<Key>
- Parameters
-
| noiseModel | Shared pointer to noise model. |
| keys | A container of keys for the variables in this factor. |
Definition at line 558 of file NonlinearFactor.h.
template<class... ValueTypes>
template<typename... OptionalJacArgs, typename = IndexIsValid<sizeof...(OptionalJacArgs) + 1>>
Some (but not all) optional Jacobians are omitted (function overload) and the jacobians are l-value references to matrices. e.g. const Vector error = factor.evaluateError(pose, point, Hpose);
Definition at line 675 of file NonlinearFactor.h.
template<class... ValueTypes>
template<typename... OptionalJacArgs, typename = IndexIsValid<sizeof...(OptionalJacArgs) + 1>>
Some (but not all) optional Jacobians are omitted (function overload) and the jacobians are pointers to matrices. e.g. const Vector error = factor.evaluateError(pose, point, &Hpose);
Definition at line 685 of file NonlinearFactor.h.
template<class... ValueTypes>
Override evaluateError to finish implementing an n-way factor.
Both the x and H arguments are written here as parameter packs, but when overriding this method, you probably want to explicitly write them out. For example, for a 2-way factor with variable types Pose3 and Point3, you should implement:
If any of the optional Matrix reference arguments are specified, it should compute both the function evaluation and its derivative(s) in the requested variables.
- Parameters
-
| x | The values of the variables to evaluate the error for. Passed in as separate arguments. |
| [out] | H | The Jacobian with respect to each variable (optional). |
template<class... ValueTypes>
template<int I = 1>
Returns a key. Usage: key<I>() returns the I'th key. I is 1-indexed for backwards compatibility/consistency! So for example,
Note that, if your class is templated AND you are trying to call key<1> inside your class, due to dependent types you need the template keyword: this->key1().
Definition at line 585 of file NonlinearFactor.h.
template<class... ValueTypes>
template<std::size_t... Indices>