GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
Public Types | Public Member Functions | Protected Types | Protected Attributes | List of all members
gtsam::MagFactor2 Class Referenceabstract

#include <MagFactor.h>

Inheritance diagram for gtsam::MagFactor2:
Inheritance graph
[legend]
Collaboration diagram for gtsam::MagFactor2:
Collaboration graph
[legend]

Public Types

enum  
 N is the number of variables (N-way factor)
 
using ValueType = typename std::tuple_element< I - 1, std::tuple< ValueTypes... > >::type
 
typedef std::shared_ptr< Thisshared_ptr
 
typedef KeyVector::iterator iterator
 Iterator over keys.
 
typedef KeyVector::const_iterator const_iterator
 Const iterator over keys.
 

Public Member Functions

 MagFactor2 (Key key1, Key key2, const Point3 &measured, const Rot3 &nRb, const SharedNoiseModel &model)
 
NonlinearFactor::shared_ptr clone () const override
 
Vector evaluateError (const Point3 &nM, const Point3 &bias, OptionalMatrixType H1, OptionalMatrixType H2) const override
 vector of errors More...
 
Key key () const
 
Vector unwhitenedError (const Values &x, std::vector< Matrix > &H) const
 
void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
 
bool equals (const NonlinearFactor &f, double tol=1e-9) const override
 
size_t dim () const override
 
const SharedNoiseModelnoiseModel () const
 access to the noise model
 
Vector whitenedError (const Values &c) const
 
Vector unweightedWhitenedError (const Values &c) const
 
double weight (const Values &c) const
 
double error (const Values &c) const override
 
std::shared_ptr< GaussianFactorlinearize (const Values &x) const override
 
shared_ptr cloneWithNewNoiseModel (const SharedNoiseModel newNoise) const
 
NoiseModelFactor methods
Vector unwhitenedError (const Values &x, OptionalMatrixVecType H=nullptr) const override
 
Virtual methods
virtual Vector evaluateError (const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
 
Vector evaluateError (const ValueTypes &... x, MatrixTypeT< ValueTypes > &... H) const
 
Convenience method overloads
Vector evaluateError (const ValueTypes &... x) const
 
AreAllMatrixRefs< Vector, OptionalJacArgs... > evaluateError (const ValueTypes &... x, OptionalJacArgs &&... H) const
 
Shortcut functions `key1()` -> `key<1>()`
Key key1 () const
 
Key key2 () const
 
Key key3 () const
 
Key key4 () const
 
Key key5 () const
 
Key key6 () const
 
Testable
bool equals (const This &other, double tol=1e-9) const
 check equality
 
virtual void printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print only keys
 
Standard Interface
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
 
Standard Interface
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 KeyVectorkeys () const
 Access the factor's involved variable keys.
 
const_iterator begin () const
 
const_iterator end () const
 
size_t size () const
 
Advanced Interface
KeyVectorkeys ()
 
iterator begin ()
 
iterator end ()
 

Protected Types

using Base = NoiseModelFactor
 
using This = NoiseModelFactorN< ValueTypes... >
 
using OptionalMatrixTypeT = Matrix *
 
using KeyType = Key
 
using MatrixTypeT = Matrix
 
SFINAE aliases
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 >
 

Static Protected Member Functions

Standard Constructors
template<typename CONTAINER >
static Factor FromKeys (const CONTAINER &keys)
 
template<typename ITERATOR >
static Factor FromIterators (ITERATOR first, ITERATOR last)
 

Protected Attributes

SharedNoiseModel noiseModel_
 
KeyVector keys_
 The keys involved in this factor.
 

Detailed Description

Factor to calibrate local Earth magnetic field as well as magnetometer bias This version uses model measured bM = bRn * nM + bias and optimizes for both nM and the bias, where nM is in units defined by magnetometer

Member Typedef Documentation

◆ AreAllMatrixPtrs

using gtsam::NoiseModelFactorN< ValueTypes >::AreAllMatrixPtrs = std::enable_if_t<(... && (IsMatrixPointer<Args>::value || IsNullpointer<Args>::value)), Ret>
protectedinherited

A helper alias to check if a list of args are all pointers to a matrix or not. It will be used to choose the right overload of evaluateError.

◆ AreAllMatrixRefs

using gtsam::NoiseModelFactorN< ValueTypes >::AreAllMatrixRefs = std::enable_if_t<(... && std::is_convertible<Args, Matrix&>::value), Ret>
protectedinherited

A helper alias to check if a list of args are all references to a matrix or not. It will be used to choose the right overload of evaluateError.

◆ shared_ptr

typedef std::shared_ptr<This> gtsam::NoiseModelFactor::shared_ptr
inherited

Noise model

◆ ValueType

using gtsam::NoiseModelFactorN< ValueTypes >::ValueType = typename std::tuple_element<I - 1, std::tuple<ValueTypes...> >::type
inherited

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> // Pose3
Factor::ValueType<2> // Point3
// Factor::ValueType<0> // ERROR! Will not compile.
// Factor::ValueType<3> // ERROR! Will not compile.

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>.

Constructor & Destructor Documentation

◆ MagFactor2()

gtsam::MagFactor2::MagFactor2 ( Key  key1,
Key  key2,
const Point3 measured,
const Rot3 nRb,
const SharedNoiseModel model 
)
inline

Constructor

Member Function Documentation

◆ active()

virtual bool gtsam::NonlinearFactor::active ( const Values ) const
inlinevirtualinherited

Checks whether a factor should be used based on a set of values. This is primarily used to implement inequality constraints that require a variable active set. For all others, the default implementation returning true solves this problem.

In an inequality/bounding constraint, this active() returns true when the constraint is NOT fulfilled.

Returns
true if the constraint is active

Reimplemented in gtsam::BoundingConstraint2< VALUE1, VALUE2 >, gtsam::AntiFactor, and gtsam::BoundingConstraint1< VALUE >.

◆ begin() [1/2]

const_iterator gtsam::Factor::begin ( ) const
inlineinherited

Iterator at beginning of involved variable keys

◆ begin() [2/2]

iterator gtsam::Factor::begin ( )
inlineinherited

Iterator at beginning of involved variable keys

◆ clone()

NonlinearFactor::shared_ptr gtsam::MagFactor2::clone ( ) const
inlineoverridevirtual
Returns
a deep copy of this factor

Reimplemented from gtsam::NonlinearFactor.

◆ cloneWithNewNoiseModel()

shared_ptr gtsam::NoiseModelFactor::cloneWithNewNoiseModel ( const SharedNoiseModel  newNoise) const
inherited

Creates a shared_ptr clone of the factor with a new noise model

◆ dim()

size_t gtsam::NoiseModelFactor::dim ( ) const
inlineoverridevirtualinherited

get the dimension of the factor (number of rows on linearization)

Implements gtsam::NonlinearFactor.

◆ end() [1/2]

const_iterator gtsam::Factor::end ( ) const
inlineinherited

Iterator at end of involved variable keys

◆ end() [2/2]

iterator gtsam::Factor::end ( )
inlineinherited

Iterator at end of involved variable keys

◆ equals()

bool gtsam::NoiseModelFactor::equals ( const NonlinearFactor f,
double  tol = 1e-9 
) const
overridevirtualinherited

Check if two factors are equal

Reimplemented from gtsam::NonlinearFactor.

Reimplemented in gtsam::GeneralSFMFactor2< CALIBRATION >, gtsam::InvDepthFactorVariant3b, gtsam::ProjectionFactorRollingShutter, gtsam::EquivInertialNavFactor_GlobalVel_NoBias< POSE, VELOCITY >, gtsam::EquivInertialNavFactor_GlobalVel< POSE, VELOCITY, IMUBIAS >, gtsam::FrobeniusBetweenFactor< Rot >, gtsam::InertialNavFactor_GlobalVelocity< POSE, VELOCITY, IMUBIAS >, gtsam::GenericProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::GeneralSFMFactor< CAMERA, LANDMARK >, gtsam::GenericStereoFactor< POSE, LANDMARK >, gtsam::ProjectionFactorPPP< POSE, LANDMARK, CALIBRATION >, gtsam::TriangulationFactor< CAMERA >, gtsam::FunctorizedFactor< Vector, ParameterMatrix< M > >, gtsam::FunctorizedFactor< double, BASIS::Parameters >, gtsam::FunctorizedFactor< double, Vector >, gtsam::FunctorizedFactor< T, ParameterMatrix< traits< T >::dimension > >, gtsam::FunctorizedFactor< double, ParameterMatrix< P > >, gtsam::ProjectionFactorPPPC< POSE, LANDMARK, CALIBRATION >, gtsam::PartialPriorFactor< VALUE >, gtsam::PartialPriorFactor< PoseRTV >, gtsam::BetweenFactor< VALUE >, gtsam::ExpressionFactor< BearingRange< A1, A2 > >, gtsam::ExpressionFactor< double >, gtsam::PriorFactor< VALUE >, gtsam::SmartRangeFactor, gtsam::GaussMarkov1stOrderFactor< VALUE >, gtsam::PoseBetweenFactor< POSE >, gtsam::InvDepthFactor3< POSE, LANDMARK, INVDEPTH >, gtsam::InvDepthFactorVariant2, gtsam::OrientedPlane3DirectionPrior, gtsam::PoseTranslationPrior< POSE >, gtsam::InvDepthFactorVariant3a, gtsam::EssentialMatrixConstraint, gtsam::InvDepthFactorVariant1, gtsam::PosePriorFactor< POSE >, gtsam::BiasedGPSFactor, gtsam::ShonanFactor< d >, gtsam::PoseRotationPrior< POSE >, gtsam::FullIMUFactor< POSE >, gtsam::PoseToPointFactor< POSE, POINT >, gtsam::RelativeElevationFactor, and gtsam::IMUFactor< POSE >.

◆ error() [1/2]

double gtsam::NonlinearFactor::error ( const HybridValues c) const
overridevirtualinherited

All factor types need to implement an error function. In factor graphs, this is the negative log-likelihood.

Reimplemented from gtsam::Factor.

◆ error() [2/2]

double gtsam::NoiseModelFactor::error ( const Values c) const
overridevirtualinherited

Calculate the error of the factor. This is the log-likelihood, e.g. \( 0.5(h(x)-z)^2/\sigma^2 \) in case of Gaussian. In this class, we take the raw prediction error \( h(x)-z \), ask the noise model to transform it to \( (h(x)-z)^2/\sigma^2 \), and then multiply by 0.5.

Reimplemented from gtsam::NonlinearFactor.

◆ evaluateError() [1/5]

Vector gtsam::MagFactor2::evaluateError ( const Point3 nM,
const Point3 bias,
OptionalMatrixType  H1,
OptionalMatrixType  H2 
) const
inlineoverride

vector of errors

Parameters
nM(unknown) local earth magnetic field vector, in nav frame
bias(unknown) 3D bias

◆ evaluateError() [2/5]

virtual Vector gtsam::NoiseModelFactorN< ValueTypes >::evaluateError ( const ValueTypes &...  x,
OptionalMatrixTypeT< ValueTypes >...  H 
) const
pure virtualinherited

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:

const Pose3& x1, const Point3& x2,
OptionalMatrixType H2 = OptionalNone) const override { ... }

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
xThe values of the variables to evaluate the error for. Passed in as separate arguments.
[out]HThe Jacobian with respect to each variable (optional).

◆ evaluateError() [3/5]

Vector gtsam::NoiseModelFactorN< ValueTypes >::evaluateError ( const ValueTypes &...  x,
MatrixTypeT< ValueTypes > &...  H 
) const
inlineinherited

If all the optional arguments are matrices then redirect the call to the one which takes pointers. To get access to this version of the function from derived classes one will need to use the "using" keyword and specify that like this: public: using NoiseModelFactorN<list the value types here>::evaluateError;

◆ evaluateError() [4/5]

Vector gtsam::NoiseModelFactorN< ValueTypes >::evaluateError ( const ValueTypes &...  x) const
inlineinherited

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);

◆ evaluateError() [5/5]

AreAllMatrixRefs<Vector, OptionalJacArgs...> gtsam::NoiseModelFactorN< ValueTypes >::evaluateError ( const ValueTypes &...  x,
OptionalJacArgs &&...  H 
) const
inlineinherited

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);

◆ FromIterators()

template<typename ITERATOR >
static Factor gtsam::Factor::FromIterators ( ITERATOR  first,
ITERATOR  last 
)
inlinestaticprotectedinherited

Construct factor from iterator keys. This is called internally from derived factor static factor methods, as a workaround for not being able to call the protected constructors above.

◆ FromKeys()

template<typename CONTAINER >
static Factor gtsam::Factor::FromKeys ( const CONTAINER &  keys)
inlinestaticprotectedinherited

Construct factor from container of keys. This is called internally from derived factor static factor methods, as a workaround for not being able to call the protected constructors above.

◆ key()

Key gtsam::NoiseModelFactorN< ValueTypes >::key ( ) const
inlineinherited

Returns a key. Usage: key<I>() returns the I'th key. I is 1-indexed for backwards compatibility/consistency! So for example,

NoiseModelFactorN<Pose3, Point3> factor(noise, key1, key2);
key<1>() // = key1
key<2>() // = key2
// key<0>() // ERROR! Will not compile
// key<3>() // ERROR! Will not compile

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().

◆ keys()

KeyVector& gtsam::Factor::keys ( )
inlineinherited
Returns
keys involved in this factor

◆ linearize()

std::shared_ptr<GaussianFactor> gtsam::NoiseModelFactor::linearize ( const Values x) const
overridevirtualinherited

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) \)

Implements gtsam::NonlinearFactor.

Reimplemented in gtsam::TriangulationFactor< CAMERA >, gtsam::GeneralSFMFactor< CAMERA, LANDMARK >, gtsam::ExpressionFactor< BearingRange< A1, A2 > >, and gtsam::ExpressionFactor< double >.

◆ print()

void gtsam::NoiseModelFactor::print ( const std::string &  s = "",
const KeyFormatter keyFormatter = DefaultKeyFormatter 
) const
overridevirtualinherited

Print

Reimplemented from gtsam::NonlinearFactor.

Reimplemented in gtsam::EssentialMatrixFactor4< CALIBRATION >, gtsam::EssentialMatrixFactor3, gtsam::GeneralSFMFactor2< CALIBRATION >, gtsam::InvDepthFactorVariant3b, gtsam::EssentialMatrixFactor2, gtsam::RangeFactorWithTransform< A1, A2, T >, gtsam::ProjectionFactorRollingShutter, gtsam::FrobeniusBetweenFactor< Rot >, gtsam::EquivInertialNavFactor_GlobalVel< POSE, VELOCITY, IMUBIAS >, gtsam::EquivInertialNavFactor_GlobalVel_NoBias< POSE, VELOCITY >, gtsam::GenericProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::InertialNavFactor_GlobalVelocity< POSE, VELOCITY, IMUBIAS >, gtsam::MultiProjectionFactor< POSE, LANDMARK, CALIBRATION >, gtsam::GeneralSFMFactor< CAMERA, LANDMARK >, gtsam::ReferenceFrameFactor< POINT, TRANSFORM >, gtsam::ProjectionFactorPPP< POSE, LANDMARK, CALIBRATION >, gtsam::GenericStereoFactor< POSE, LANDMARK >, gtsam::TriangulationFactor< CAMERA >, gtsam::FunctorizedFactor< Vector, ParameterMatrix< M > >, gtsam::FunctorizedFactor< double, BASIS::Parameters >, gtsam::FunctorizedFactor< double, Vector >, gtsam::FunctorizedFactor< T, ParameterMatrix< traits< T >::dimension > >, gtsam::FunctorizedFactor< double, ParameterMatrix< P > >, gtsam::RotateDirectionsFactor, gtsam::VelocityConstraint, gtsam::ProjectionFactorPPPC< POSE, LANDMARK, CALIBRATION >, gtsam::PartialPriorFactor< VALUE >, gtsam::PartialPriorFactor< PoseRTV >, gtsam::BetweenFactor< VALUE >, gtsam::BearingRangeFactor< A1, A2, B, R >, gtsam::EssentialMatrixFactor, gtsam::PoseTranslationPrior< POSE >, gtsam::ExpressionFactor< BearingRange< A1, A2 > >, gtsam::ExpressionFactor< double >, gtsam::SmartRangeFactor, gtsam::PriorFactor< VALUE >, gtsam::GaussMarkov1stOrderFactor< VALUE >, gtsam::RangeFactor< A1, A2, T >, gtsam::OrientedPlane3DirectionPrior, gtsam::EssentialMatrixConstraint, gtsam::PoseRotationPrior< POSE >, gtsam::InvDepthFactor3< POSE, LANDMARK, INVDEPTH >, gtsam::InvDepthFactorVariant2, gtsam::InvDepthFactorVariant3a, gtsam::LocalOrientedPlane3Factor, gtsam::PoseBetweenFactor< POSE >, gtsam::InvDepthFactorVariant1, gtsam::FullIMUFactor< POSE >, gtsam::PosePriorFactor< POSE >, gtsam::ShonanFactor< d >, gtsam::RelativeElevationFactor, gtsam::IMUFactor< POSE >, gtsam::BiasedGPSFactor, gtsam::BearingFactor< A1, A2, T >, gtsam::PoseToPointFactor< POSE, POINT >, gtsam::RotateFactor, and gtsam::OrientedPlane3Factor.

◆ rekey() [1/2]

virtual shared_ptr gtsam::NonlinearFactor::rekey ( const std::map< Key, Key > &  rekey_mapping) const
virtualinherited

Creates a shared_ptr clone of the factor with different keys using a map from old->new keys

Reimplemented in gtsam::LinearContainerFactor.

◆ rekey() [2/2]

virtual shared_ptr gtsam::NonlinearFactor::rekey ( const KeyVector new_keys) const
virtualinherited

Clones a factor and fully replaces its keys

Parameters
new_keysis the full replacement set of keys

Reimplemented in gtsam::LinearContainerFactor.

◆ sendable()

virtual bool gtsam::NonlinearFactor::sendable ( ) const
inlinevirtualinherited

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)

Reimplemented in gtsam::CustomFactor.

◆ size()

size_t gtsam::Factor::size ( ) const
inlineinherited
Returns
the number of variables involved in this factor

◆ unweightedWhitenedError()

Vector gtsam::NoiseModelFactor::unweightedWhitenedError ( const Values c) const
inherited

Vector of errors, whitened, but unweighted by any loss function

◆ unwhitenedError() [1/2]

Vector gtsam::NoiseModelFactor::unwhitenedError ( const Values x,
std::vector< Matrix > &  H 
) const
inlineinherited

support taking in the actual vector instead of the pointer as well to get access to this version of the function from derived classes one will need to use the "using" keyword and specify that like this: public: using NoiseModelFactor::unwhitenedError;

◆ unwhitenedError() [2/2]

Vector gtsam::NoiseModelFactorN< ValueTypes >::unwhitenedError ( const Values x,
OptionalMatrixVecType  H = nullptr 
) const
inlineoverridevirtualinherited

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:

values.insert(...) // populate values
std::vector<Matrix> Hs(2); // this will be an optional output argument
const Vector error = factor.unwhitenedError(values, Hs);
Parameters
[in]xA Values object containing the values of all the variables used in this factor
[out]HA 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.

◆ weight()

double gtsam::NoiseModelFactor::weight ( const Values c) const
inherited

Compute the effective weight of the factor from the noise model.

◆ whitenedError()

Vector gtsam::NoiseModelFactor::whitenedError ( const Values c) const
inherited

Vector of errors, whitened This is the raw error, i.e., i.e. \( (h(x)-z)/\sigma \) in case of a Gaussian


The documentation for this class was generated from the following file: