gtsam  4.0.0
gtsam
gtsam::SmartRangeFactor Class Reference
+ Inheritance diagram for gtsam::SmartRangeFactor:

Public Member Functions

 SmartRangeFactor ()
 Default constructor: don't use directly.
 
 SmartRangeFactor (double s)
 Constructor. More...
 
void addRange (Key key, double measuredRange)
 Add a range measurement to a pose with given key.
 
virtual void print (const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
 print
 
virtual bool equals (const NonlinearFactor &f, double tol=1e-9) const
 Check if two factors are equal.
 
Point2 triangulate (const Values &x) const
 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.
 
virtual Vector unwhitenedError (const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const
 Error function without the NoiseModel, \( z-h(x) \).
 
virtual gtsam::NonlinearFactor::shared_ptr clone () const
 

Classes

struct  Circle2
 

Protected Types

typedef SmartRangeFactor This
 

Protected Attributes

std::vector< double > measurements_
 Range measurements.
 
double variance_
 variance on noise
 

Constructor & Destructor Documentation

◆ SmartRangeFactor()

gtsam::SmartRangeFactor::SmartRangeFactor ( double  s)
inlineexplicit

Constructor.

Parameters
sstandard deviation of range measurement noise

Member Function Documentation

◆ clone()

virtual gtsam::NonlinearFactor::shared_ptr gtsam::SmartRangeFactor::clone ( ) const
inlinevirtual
Returns
a deep copy of this factor

Reimplemented from gtsam::NonlinearFactor.


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