#include <SmartRangeFactor.h>
Classes | |
struct | Circle2 |
Public Member Functions | |
void | addRange (Key key, double measuredRange) |
Add a range measurement to a pose with given key. More... | |
gtsam::NonlinearFactor::shared_ptr | clone () const override |
bool | equals (const NonlinearFactor &f, double tol=1e-9) const override |
void | print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override |
SmartRangeFactor () | |
SmartRangeFactor (double s) | |
Point2 | triangulate (const Values &x) const |
Vector | unwhitenedError (const Values &x, OptionalMatrixVecType H=nullptr) const override |
virtual Vector | unwhitenedError (const Values &x, OptionalMatrixVecType H=nullptr) const=0 |
Vector | unwhitenedError (const Values &x, std::vector< Matrix > &H) const |
~SmartRangeFactor () override | |
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 SmartRangeFactor | 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 |
Protected Attributes | |
std::vector< double > | measurements_ |
Range measurements. More... | |
double | variance_ |
variance on noise 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 | |
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... | |
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) | |
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) |
Smart factor for range SLAM
Definition at line 30 of file SmartRangeFactor.h.
|
protected |
Definition at line 40 of file SmartRangeFactor.h.
|
inline |
Default constructor: don't use directly
Definition at line 51 of file SmartRangeFactor.h.
|
inlineexplicit |
Constructor
s | standard deviation of range measurement noise |
Definition at line 58 of file SmartRangeFactor.h.
|
inlineoverride |
Definition at line 62 of file SmartRangeFactor.h.
|
inline |
Add a range measurement to a pose with given key.
Definition at line 66 of file SmartRangeFactor.h.
|
inlineoverridevirtual |
Reimplemented from gtsam::NonlinearFactor.
Definition at line 182 of file SmartRangeFactor.h.
|
inlineoverridevirtual |
Check if two factors are equal
Reimplemented from gtsam::NoiseModelFactor.
Definition at line 88 of file SmartRangeFactor.h.
|
inlineoverridevirtual |
Triangulate a point from at least three pose-range pairs Checks for best pair that includes first point Raise runtime_error if not well defined.
Definition at line 99 of file SmartRangeFactor.h.
|
inlineoverridevirtual |
Error function without the NoiseModel, .
Implements gtsam::NoiseModelFactor.
Definition at line 151 of file SmartRangeFactor.h.
virtual Vector gtsam::NoiseModelFactor::unwhitenedError |
Error function without the NoiseModel, . Override this method to finish implementing an N-way factor. If the optional arguments is specified, it should compute both the function evaluation and its derivative(s) in H.
|
inline |
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;
Definition at line 263 of file NonlinearFactor.h.
|
protected |
Range measurements.
Definition at line 42 of file SmartRangeFactor.h.
|
protected |
variance on noise
Definition at line 43 of file SmartRangeFactor.h.