template<class VALUE>
class gtsam::BetweenConstraint< VALUE >
Binary between constraint - forces between to a given value This constraint requires the underlying type to a Lie type.
|
| BetweenConstraint (const VALUE &measured, Key key1, Key key2, double mu=1000.0) |
| Syntactic sugar for constrained version.
|
|
| BetweenFactor () |
| default constructor - only use for serialization
|
|
| BetweenFactor (Key key1, Key key2, const VALUE &measured, const SharedNoiseModel &model=nullptr) |
| Constructor.
|
|
virtual gtsam::NonlinearFactor::shared_ptr | clone () const |
|
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 T &p1, const T &p2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const |
| implement functions needed to derive from Factor More...
|
|
const VALUE & | measured () const |
| return the measured
|
|
std::size_t | size () const |
| number of variables attached to this factor
|
|
| 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...
|
|