gtsam 4.2.0
gtsam
|
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:
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).
Public Member Functions | |
template<int I = 1> | |
Key | key () const |
Returns a key. More... | |
Constructors | |
NoiseModelFactorN () | |
Default Constructor for I/O. | |
NoiseModelFactorN (const SharedNoiseModel &noiseModel, KeyType< ValueTypes >... keys) | |
Constructor. More... | |
template<typename CONTAINER = std::initializer_list<Key>, typename = IsContainerOfKeys<CONTAINER>> | |
NoiseModelFactorN (const SharedNoiseModel &noiseModel, CONTAINER keys) | |
Constructor. More... | |
NoiseModelFactor methods | |
Vector | unwhitenedError (const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override |
This implements the unwhitenedError virtual function by calling the n-key specific version of evaluateError, which is pure virtual so must be implemented in the derived class. More... | |
Virtual methods | |
virtual Vector | evaluateError (const ValueTypes &... x, OptionalMatrix< ValueTypes >... H) const =0 |
Override evaluateError to finish implementing an n-way factor. More... | |
Convenience method overloads | |
Vector | evaluateError (const ValueTypes &... x) const |
No-Jacobians requested function overload. More... | |
template<typename... OptionalJacArgs, typename = IndexIsValid<sizeof...(OptionalJacArgs) + 1>> | |
Vector | evaluateError (const ValueTypes &... x, OptionalJacArgs &&... H) const |
Some (but not all) optional Jacobians are omitted (function overload) More... | |
Shortcut functions <tt>key1()</tt> -> <tt>key\<1\>()</tt> | |
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 |
![]() | |
NoiseModelFactor () | |
Default constructor for I/O only. | |
~NoiseModelFactor () override | |
Destructor. | |
template<typename CONTAINER > | |
NoiseModelFactor (const SharedNoiseModel &noiseModel, const CONTAINER &keys) | |
Constructor. | |
void | print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override |
Print. More... | |
bool | equals (const NonlinearFactor &f, double tol=1e-9) const override |
Check if two factors are equal. More... | |
size_t | dim () const override |
get the dimension of the factor (number of rows on linearization) More... | |
const SharedNoiseModel & | noiseModel () const |
access to the noise model | |
virtual Vector | unwhitenedError (const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const =0 |
Error function without the NoiseModel, \( z-h(x) \). More... | |
Vector | whitenedError (const Values &c) const |
Vector of errors, whitened This is the raw error, i.e., i.e. More... | |
Vector | unweightedWhitenedError (const Values &c) const |
Vector of errors, whitened, but unweighted by any loss function. | |
double | weight (const Values &c) const |
Compute the effective weight of the factor from the noise model. | |
double | error (const Values &c) const override |
Calculate the error of the factor. More... | |
boost::shared_ptr< GaussianFactor > | linearize (const Values &x) const override |
Linearize a non-linearFactorN to get a GaussianFactor, \( Ax-b \approx h(x+\delta x)-z = h(x) + A \delta x - z \) Hence \( b = z - h(x) = - \mathtt{error\_vector}(x) \). More... | |
shared_ptr | cloneWithNewNoiseModel (const SharedNoiseModel newNoise) const |
Creates a shared_ptr clone of the factor with a new noise model. | |
![]() | |
NonlinearFactor () | |
Default constructor for I/O only. | |
template<typename CONTAINER > | |
NonlinearFactor (const CONTAINER &keys) | |
Constructor from a collection of the keys involved in this factor. | |
virtual | ~NonlinearFactor () |
Destructor. | |
double | error (const HybridValues &c) const override |
All factor types need to implement an error function. More... | |
virtual bool | active (const Values &) const |
Checks whether a factor should be used based on a set of values. More... | |
virtual shared_ptr | clone () const |
Creates a shared_ptr clone of the factor - needs to be specialized to allow for subclasses. More... | |
virtual shared_ptr | rekey (const std::map< Key, Key > &rekey_mapping) const |
Creates a shared_ptr clone of the factor with different keys using a map from old->new keys. More... | |
virtual shared_ptr | rekey (const KeyVector &new_keys) const |
Clones a factor and fully replaces its keys. More... | |
virtual bool | sendable () const |
Should the factor be evaluated in the same thread as the caller This is to enable factors that has shared states (like the Python GIL lock) More... | |
![]() | |
virtual | ~Factor ()=default |
Default destructor. | |
bool | empty () const |
Whether the factor is empty (involves zero variables). | |
Key | front () const |
First key. | |
Key | back () const |
Last key. | |
const_iterator | find (Key key) const |
find | |
const KeyVector & | keys () const |
Access the factor's involved variable keys. | |
const_iterator | begin () const |
Iterator at beginning of involved variable keys. | |
const_iterator | end () const |
Iterator at end of involved variable keys. | |
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 | |
KeyVector & | keys () |
iterator | begin () |
Iterator at beginning of involved variable keys. | |
iterator | end () |
Iterator at end of involved variable keys. | |
Public Types | |
enum | { N = sizeof...(ValueTypes) } |
N is the number of variables (N-way factor) | |
template<int I, typename = IndexIsValid<I>> | |
using | ValueType = typename std::tuple_element< I - 1, std::tuple< ValueTypes... > >::type |
The type of the I'th template param can be obtained as ValueType. More... | |
![]() | |
typedef boost::shared_ptr< This > | shared_ptr |
Noise model. | |
![]() | |
typedef boost::shared_ptr< This > | shared_ptr |
![]() | |
typedef KeyVector::iterator | iterator |
Iterator over keys. | |
typedef KeyVector::const_iterator | const_iterator |
Const iterator over keys. | |
Protected Types | |
using | Base = NoiseModelFactor |
using | This = NoiseModelFactorN< ValueTypes... > |
template<typename T > | |
using | OptionalMatrix = boost::optional< Matrix & > |
template<typename T > | |
using | KeyType = Key |
SFINAE aliases | |
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 > |
![]() | |
typedef NonlinearFactor | Base |
typedef NoiseModelFactor | This |
![]() | |
typedef Factor | Base |
typedef NonlinearFactor | This |
Friends | |
class | boost::serialization::access |
Serialization function. | |
Additional Inherited Members | |
![]() | |
NoiseModelFactor (const SharedNoiseModel &noiseModel) | |
Constructor - only for subclasses, as this does not set keys. | |
![]() | |
Factor () | |
Default constructor for I/O. | |
template<typename CONTAINER > | |
Factor (const CONTAINER &keys) | |
Construct factor from container of keys. More... | |
template<typename ITERATOR > | |
Factor (ITERATOR first, ITERATOR last) | |
Construct factor from iterator keys. More... | |
![]() | |
template<typename CONTAINER > | |
static Factor | FromKeys (const CONTAINER &keys) |
Construct factor from container of keys. More... | |
template<typename ITERATOR > | |
static Factor | FromIterators (ITERATOR first, ITERATOR last) |
Construct factor from iterator keys. More... | |
![]() | |
SharedNoiseModel | noiseModel_ |
![]() | |
KeyVector | keys_ |
The keys involved in this factor. | |
using gtsam::NoiseModelFactorN< ValueTypes >::ValueType = typename std::tuple_element<I - 1, std::tuple<ValueTypes...> >::type |
The type of the I'th template param can be obtained as ValueType.
I is 1-indexed for backwards compatibility/consistency! So for example,
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>
.
|
inline |
Constructor.
Example usage: NoiseModelFactorN(noise, key1, key2, ..., keyN)
noiseModel | Shared pointer to noise model. |
keys | Keys for the variables in this factor, passed in as separate arguments. |
|
inline |
Constructor.
Example usage: NoiseModelFactorN(noise, {key1, key2, ..., keyN})
Example usage: NoiseModelFactorN(noise, keys)
where keys is a vector<Key>
noiseModel | Shared pointer to noise model. |
keys | A container of keys for the variables in this factor. |
|
inline |
No-Jacobians requested function overload.
This specializes the version below to avoid recursive calls since this is commonly used.
e.g. const Vector error = factor.evaluateError(pose, point);
|
inline |
Some (but not all) optional Jacobians are omitted (function overload)
e.g. const Vector error = factor.evaluateError(pose, point, Hpose);
|
pure virtual |
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.
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). |
|
inline |
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()
.
|
inlineoverridevirtual |
This implements the unwhitenedError
virtual function by calling the n-key specific version of evaluateError, which is pure virtual so must be implemented in the derived class.
Example usage:
[in] | x | A Values object containing the values of all the variables used in this factor |
[out] | H | A vector of (dynamic) matrices whose size should be equal to n. The Jacobians w.r.t. each variable will be output in this parameter. |
Implements gtsam::NoiseModelFactor.