#include <PartialPriorFactor.h>
Public Types | |
typedef VALUE | T |
Public Types inherited from gtsam::NoiseModelFactorN< VALUE > | |
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 | |
gtsam::NonlinearFactor::shared_ptr | clone () const override |
bool | equals (const NonlinearFactor &expected, double tol=1e-9) const override |
Vector | evaluateError (const T &p, OptionalMatrixType H) const override |
const std::vector< size_t > & | indices () const |
PartialPriorFactor () | |
PartialPriorFactor (Key key, const std::vector< size_t > &indices, const Vector &prior, const SharedNoiseModel &model) | |
PartialPriorFactor (Key key, size_t idx, double prior, const SharedNoiseModel &model) | |
void | print (const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override |
const Vector & | prior () const |
~PartialPriorFactor () override | |
Public Member Functions inherited from gtsam::NoiseModelFactorN< VALUE > | |
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 |
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 Types | |
typedef NoiseModelFactorN< VALUE > | Base |
typedef PartialPriorFactor< VALUE > | This |
Protected Types inherited from gtsam::NoiseModelFactorN< VALUE > | |
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 |
Protected Member Functions | |
PartialPriorFactor (Key key, const SharedNoiseModel &model) | |
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) | |
Protected Attributes | |
std::vector< size_t > | indices_ |
Indices of the measured tangent space parameters. More... | |
Vector | prior_ |
Measurement on tangent space parameters, in compressed form. More... | |
Protected Attributes inherited from gtsam::NoiseModelFactor | |
SharedNoiseModel | noiseModel_ |
Protected Attributes inherited from gtsam::Factor | |
KeyVector | keys_ |
The keys involved in this factor. More... | |
Additional Inherited Members | |
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) |
A class for a soft partial prior on any Lie type, with a mask over Expmap parameters. Note that this will use Logmap() to find a tangent space parameterization for the variable attached, so this may fail for highly nonlinear manifolds.
The prior vector used in this factor is stored in compressed form, such that it only contains values for measurements that are to be compared, and they are in the same order as VALUE::Logmap(). The provided indices will determine which components to extract in the error function.
VALUE | is the type of variable the prior effects |
Definition at line 38 of file PartialPriorFactor.h.
|
protected |
Definition at line 47 of file PartialPriorFactor.h.
typedef VALUE gtsam::PartialPriorFactor< VALUE >::T |
Definition at line 41 of file PartialPriorFactor.h.
|
protected |
Definition at line 48 of file PartialPriorFactor.h.
|
inlineprotected |
constructor with just minimum requirements for a factor - allows more computation in the constructor. This should only be used by subclasses
Definition at line 57 of file PartialPriorFactor.h.
|
inline |
default constructor - only use for serialization
Definition at line 66 of file PartialPriorFactor.h.
|
inline |
Single Element Constructor: Prior on a single parameter at index 'idx' in the tangent vector.
Definition at line 69 of file PartialPriorFactor.h.
|
inline |
Indices Constructor: Specify the relevant measured indices in the tangent vector.
Definition at line 77 of file PartialPriorFactor.h.
|
inlineoverride |
Definition at line 86 of file PartialPriorFactor.h.
|
inlineoverridevirtual |
Reimplemented from gtsam::NonlinearFactor.
Definition at line 89 of file PartialPriorFactor.h.
|
inlineoverridevirtual |
equals
Reimplemented from gtsam::NoiseModelFactor.
Definition at line 102 of file PartialPriorFactor.h.
|
inlineoverride |
implement functions needed to derive from Factor Returns a vector of errors for the measured tangent parameters.
Definition at line 112 of file PartialPriorFactor.h.
|
inline |
Definition at line 140 of file PartialPriorFactor.h.
|
inlineoverridevirtual |
implement functions needed for Testable print
Reimplemented from gtsam::NoiseModelFactor.
Definition at line 96 of file PartialPriorFactor.h.
|
inline |
Definition at line 139 of file PartialPriorFactor.h.
|
protected |
Indices of the measured tangent space parameters.
Definition at line 51 of file PartialPriorFactor.h.
|
protected |
Measurement on tangent space parameters, in compressed form.
Definition at line 50 of file PartialPriorFactor.h.