gtsam 4.1.1
gtsam
|
A convenient base class for creating your own NoiseModelFactor with 1 variable.
To derive from this class, implement evaluateError().
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 | |
Constructors | |
NoiseModelFactor1 () | |
Default constructor for I/O only. | |
~NoiseModelFactor1 () override | |
Key | key () const |
NoiseModelFactor1 (const SharedNoiseModel &noiseModel, Key key1) | |
Constructor. More... | |
NoiseModelFactor methods | |
Vector | unwhitenedError (const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override |
Calls the 1-key specific version of evaluateError below, which is pure virtual so must be implemented in the derived class. More... | |
Virtual methods | |
virtual Vector | evaluateError (const X &x, boost::optional< Matrix & > H=boost::none) const =0 |
Override this method to finish implementing a unary factor. More... | |
Public Member Functions inherited from gtsam::NoiseModelFactor | |
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. | |
Public Member Functions inherited from gtsam::NonlinearFactor | |
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. | |
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... | |
Public Member Functions inherited from gtsam::Factor | |
virtual | ~Factor ()=default |
Default destructor. | |
KeyVector & | keys () |
iterator | begin () |
Iterator at beginning of involved variable keys. | |
iterator | end () |
Iterator at end of involved variable keys. | |
virtual void | printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const |
print only keys More... | |
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 |
Public Types | |
typedef VALUE | X |
Public Types inherited from gtsam::NoiseModelFactor | |
typedef boost::shared_ptr< This > | shared_ptr |
Noise model. | |
Public Types inherited from gtsam::NonlinearFactor | |
typedef boost::shared_ptr< This > | shared_ptr |
Public Types inherited from gtsam::Factor | |
typedef KeyVector::iterator | iterator |
Iterator over keys. | |
typedef KeyVector::const_iterator | const_iterator |
Const iterator over keys. | |
Protected Types | |
typedef NoiseModelFactor | Base |
typedef NoiseModelFactor1< VALUE > | This |
Protected Types inherited from gtsam::NoiseModelFactor | |
typedef NonlinearFactor | Base |
typedef NoiseModelFactor | This |
Protected Types inherited from gtsam::NonlinearFactor | |
typedef Factor | Base |
typedef NonlinearFactor | This |
Friends | |
class | boost::serialization::access |
Serialization function. | |
Additional Inherited Members | |
Protected Member Functions inherited from gtsam::NoiseModelFactor | |
NoiseModelFactor (const SharedNoiseModel &noiseModel) | |
Constructor - only for subclasses, as this does not set keys. | |
Protected Member Functions inherited from gtsam::Factor | |
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... | |
bool | equals (const This &other, double tol=1e-9) const |
check equality | |
Static Protected Member Functions inherited from gtsam::Factor | |
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... | |
Protected Attributes inherited from gtsam::NoiseModelFactor | |
SharedNoiseModel | noiseModel_ |
Protected Attributes inherited from gtsam::Factor | |
KeyVector | keys_ |
The keys involved in this factor. | |
|
inline |
Constructor.
noiseModel | shared pointer to noise model |
key1 | by which to look up X value in Values |
|
pure virtual |
Override this method to finish implementing a unary factor.
If the optional Matrix reference argument is specified, it should compute both the function evaluation and its derivative in X.
Implemented in gtsam::FunctorizedFactor< double, BASIS::Parameters >, gtsam::EssentialMatrixFactor, gtsam::GPSFactor2, gtsam::OrientedPlane3DirectionPrior, gtsam::FunctorizedFactor< Vector, ParameterMatrix< M > >, gtsam::FunctorizedFactor< double, ParameterMatrix< P > >, gtsam::TriangulationFactor< CAMERA >, gtsam::MagPoseFactor< POSE >, gtsam::PosePriorFactor< POSE >, gtsam::PoseRotationPrior< POSE >, gtsam::PoseTranslationPrior< POSE >, gtsam::Pose3AttitudeFactor, gtsam::GPSFactor, gtsam::FrobeniusPrior< Rot >, gtsam::MagFactor, gtsam::RotateDirectionsFactor, gtsam::Rot3AttitudeFactor, gtsam::MagFactor1, gtsam::RotateFactor, gtsam::PartialPriorFactor< VALUE >, gtsam::PartialPriorFactor< PoseRTV >, gtsam::FunctorizedFactor< R, T >, gtsam::PriorFactor< VALUE >, gtsam::NonlinearEquality< VALUE >, gtsam::FunctorizedFactor< double, Vector >, gtsam::BoundingConstraint1< VALUE >, and gtsam::NonlinearEquality1< VALUE >.
|
inlineoverridevirtual |
Calls the 1-key specific version of evaluateError below, which is pure virtual so must be implemented in the derived class.
Implements gtsam::NoiseModelFactor.