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

Public Member Functions

 BiasedGPSFactor ()
 default constructor - only use for serialization
 
 BiasedGPSFactor (Key posekey, Key biaskey, const Point3 measured, const SharedNoiseModel &model)
 Constructor.
 
virtual void print (const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
 implement functions needed for Testable More...
 
virtual bool equals (const NonlinearFactor &expected, double tol=1e-9) const
 equals
 
Vector evaluateError (const Pose3 &pose, const Point3 &bias, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const
 implement functions needed to derive from Factor More...
 
const Point3 measured () const
 return the measured
 
- Public Member Functions inherited from gtsam::NoiseModelFactor2< Pose3, Point3 >
 NoiseModelFactor2 ()
 Default Constructor for I/O.
 
 NoiseModelFactor2 (const SharedNoiseModel &noiseModel, Key j1, Key j2)
 Constructor. More...
 
Key key1 () const
 methods to retrieve both keys
 
Key key2 () const
 
virtual Vector unwhitenedError (const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const
 Calls the 2-key specific version of evaluateError, which is pure virtual so must be implemented in the derived class. More...
 
- Public Member Functions inherited from gtsam::NoiseModelFactor
 NoiseModelFactor ()
 Default constructor for I/O only.
 
virtual ~NoiseModelFactor ()
 Destructor.
 
template<typename CONTAINER >
 NoiseModelFactor (const SharedNoiseModel &noiseModel, const CONTAINER &keys)
 Constructor.
 
virtual size_t dim () const
 get the dimension of the factor (number of rows on linearization)
 
const SharedNoiseModelnoiseModel () const
 access to the noise model
 
Vector whitenedError (const Values &c) const
 Vector of errors, whitened This is the raw error, i.e., i.e. More...
 
virtual double error (const Values &c) const
 Calculate the error of the factor. More...
 
boost::shared_ptr< GaussianFactorlinearize (const Values &x) const
 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) \).
 
- 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...
 
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.
 
shared_ptr rekey (const KeyVector &new_keys) const
 Clones a factor and fully replaces its keys. More...
 
- Public Member Functions inherited from gtsam::Factor
KeyVectorkeys ()
 
iterator begin ()
 Iterator at beginning of involved variable keys.
 
iterator end ()
 Iterator at end of involved variable keys.
 
void print (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print
 
void printKeys (const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
 print only keys
 
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
 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 boost::shared_ptr< BiasedGPSFactorshared_ptr
 The measurement.
 
- Public Types inherited from gtsam::NoiseModelFactor2< Pose3, Point3 >
typedef Pose3 X1
 
typedef Point3 X2
 
- Public Types inherited from gtsam::NoiseModelFactor
typedef boost::shared_ptr< Thisshared_ptr
 Noise model.
 
- Public Types inherited from gtsam::NonlinearFactor
typedef boost::shared_ptr< Thisshared_ptr
 
- Public Types inherited from gtsam::Factor
typedef KeyVector::iterator iterator
 Iterator over keys.
 
typedef KeyVector::const_iterator const_iterator
 Const iterator over keys.
 

Friends

class boost::serialization::access
 Serialization function.
 

Additional Inherited Members

- Protected Types inherited from gtsam::NoiseModelFactor2< Pose3, Point3 >
typedef NoiseModelFactor Base
 
typedef NoiseModelFactor2< Pose3, Point3This
 
- 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 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.
 

Member Function Documentation

◆ evaluateError()

Vector gtsam::BiasedGPSFactor::evaluateError ( const Pose3 pose,
const Point3 bias,
boost::optional< Matrix & >  H1 = boost::none,
boost::optional< Matrix & >  H2 = boost::none 
) const
inlinevirtual

implement functions needed to derive from Factor

vector of errors

Implements gtsam::NoiseModelFactor2< Pose3, Point3 >.

◆ print()

virtual void gtsam::BiasedGPSFactor::print ( const std::string &  s,
const KeyFormatter keyFormatter = DefaultKeyFormatter 
) const
inlinevirtual

implement functions needed for Testable

print

Reimplemented from gtsam::NoiseModelFactor.


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