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

Public Member Functions

 VelocityConstraint3 (Key key1, Key key2, Key velKey, double dt, double mu=1000.0)
 TODO: comment.
 
virtual gtsam::NonlinearFactor::shared_ptr clone () const
 
Vector evaluateError (const double &x1, const double &x2, const double &v, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const
 x1 + v*dt - x2 = 0, with optional derivatives
 
- Public Member Functions inherited from gtsam::NoiseModelFactor3< double, double, double >
 NoiseModelFactor3 ()
 Default Constructor for I/O.
 
 NoiseModelFactor3 (const SharedNoiseModel &noiseModel, Key j1, Key j2, Key j3)
 Constructor. More...
 
Key key1 () const
 methods to retrieve keys
 
Key key2 () const
 
Key key3 () const
 
virtual Vector unwhitenedError (const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const
 Calls the 3-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 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.
 
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 Types

typedef boost::shared_ptr< VelocityConstraint3shared_ptr
 
- Public Types inherited from gtsam::NoiseModelFactor3< double, double, double >
typedef double X1
 
typedef double X2
 
typedef double X3
 
- Public Types inherited from gtsam::NoiseModelFactor
typedef boost::shared_ptr< Thisshared_ptr
 Noise model.
 

Protected Types

typedef NoiseModelFactor3< double, double, double > Base
 
- Protected Types inherited from gtsam::NoiseModelFactor3< double, double, double >
typedef NoiseModelFactor Base
 
typedef NoiseModelFactor3< double, double, double > This
 
- Protected Types inherited from gtsam::NoiseModelFactor
typedef NonlinearFactor Base
 
typedef NoiseModelFactor This
 

Protected Member Functions

 VelocityConstraint3 ()
 default constructor to allow for serialization
 
- Protected Member Functions inherited from gtsam::NoiseModelFactor
 NoiseModelFactor (const SharedNoiseModel &noiseModel)
 Constructor - only for subclasses, as this does not set keys.
 

Protected Attributes

double dt_
 
- Protected Attributes inherited from gtsam::NoiseModelFactor
SharedNoiseModel noiseModel_
 

Friends

class boost::serialization::access
 Serialization function.
 

Member Function Documentation

◆ clone()

virtual gtsam::NonlinearFactor::shared_ptr gtsam::VelocityConstraint3::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: