Removed old "Config" template arguments in favor of VALUES
parent
92bdd2b43c
commit
5268de198d
|
|
@ -27,21 +27,21 @@ namespace gtsam {
|
|||
/**
|
||||
* Non-linear factor for a constraint derived from a 2D measurement. The calibration is unknown here compared to GenericProjectionFactor
|
||||
*/
|
||||
template <class Cfg, class CamK, class LmK>
|
||||
template <class VALUES, class CamK, class LmK>
|
||||
class GeneralSFMFactor:
|
||||
public NonlinearFactor2<Cfg, CamK, LmK> {
|
||||
public NonlinearFactor2<VALUES, CamK, LmK> {
|
||||
protected:
|
||||
Point2 z_;
|
||||
|
||||
public:
|
||||
|
||||
typedef typename CamK::Value Cam;
|
||||
typedef GeneralSFMFactor<Cfg, CamK, LmK> Self ;
|
||||
typedef NonlinearFactor2<Cfg, CamK, LmK> Base;
|
||||
typedef GeneralSFMFactor<VALUES, CamK, LmK> Self ;
|
||||
typedef NonlinearFactor2<VALUES, CamK, LmK> Base;
|
||||
typedef Point2 Measurement;
|
||||
|
||||
// shorthand for a smart pointer to a factor
|
||||
typedef boost::shared_ptr<GeneralSFMFactor<Cfg, LmK, CamK> > shared_ptr;
|
||||
typedef boost::shared_ptr<GeneralSFMFactor<VALUES, LmK, CamK> > shared_ptr;
|
||||
|
||||
/**
|
||||
* Constructor
|
||||
|
|
@ -71,7 +71,7 @@ namespace gtsam {
|
|||
/**
|
||||
* equals
|
||||
*/
|
||||
bool equals(const GeneralSFMFactor<Cfg, CamK, LmK> &p, double tol = 1e-9) const {
|
||||
bool equals(const GeneralSFMFactor<VALUES, CamK, LmK> &p, double tol = 1e-9) const {
|
||||
return Base::equals(p, tol) && this->z_.equals(p.z_, tol) ;
|
||||
}
|
||||
|
||||
|
|
|
|||
|
|
@ -29,8 +29,8 @@ namespace gtsam {
|
|||
* Non-linear factor for a constraint derived from a 2D measurement. The calibration is known here.
|
||||
* i.e. the main building block for visual SLAM.
|
||||
*/
|
||||
template <class CFG, class LMK, class POSK>
|
||||
class GenericProjectionFactor : public NonlinearFactor2<CFG, POSK, LMK>, Testable<GenericProjectionFactor<CFG, LMK, POSK> > {
|
||||
template <class VALUES, class LMK, class POSK>
|
||||
class GenericProjectionFactor : public NonlinearFactor2<VALUES, POSK, LMK>, Testable<GenericProjectionFactor<VALUES, LMK, POSK> > {
|
||||
protected:
|
||||
|
||||
// Keep a copy of measurement and calibration for I/O
|
||||
|
|
@ -40,10 +40,10 @@ namespace gtsam {
|
|||
public:
|
||||
|
||||
// shorthand for base class type
|
||||
typedef NonlinearFactor2<CFG, POSK, LMK> Base;
|
||||
typedef NonlinearFactor2<VALUES, POSK, LMK> Base;
|
||||
|
||||
// shorthand for a smart pointer to a factor
|
||||
typedef boost::shared_ptr<GenericProjectionFactor<CFG, LMK, POSK> > shared_ptr;
|
||||
typedef boost::shared_ptr<GenericProjectionFactor<VALUES, LMK, POSK> > shared_ptr;
|
||||
|
||||
/**
|
||||
* Default constructor
|
||||
|
|
@ -76,7 +76,7 @@ namespace gtsam {
|
|||
/**
|
||||
* equals
|
||||
*/
|
||||
bool equals(const GenericProjectionFactor<CFG, LMK, POSK>& p, double tol = 1e-9) const {
|
||||
bool equals(const GenericProjectionFactor<VALUES, LMK, POSK>& p, double tol = 1e-9) const {
|
||||
return Base::equals(p, tol) && this->z_.equals(p.z_, tol)
|
||||
&& this->K_->equals(*p.K_, tol);
|
||||
}
|
||||
|
|
|
|||
|
|
@ -111,18 +111,18 @@ namespace gtsam {
|
|||
/**
|
||||
* Unary factor encoding a soft prior on a vector
|
||||
*/
|
||||
template<class CFG = Values, class KEY = PoseKey>
|
||||
class GenericPrior: public NonlinearFactor1<CFG, KEY> {
|
||||
template<class VALUES = Values, class KEY = PoseKey>
|
||||
class GenericPrior: public NonlinearFactor1<VALUES, KEY> {
|
||||
public:
|
||||
typedef NonlinearFactor1<CFG, KEY> Base; ///< base class
|
||||
typedef boost::shared_ptr<GenericPrior<CFG, KEY> > shared_ptr;
|
||||
typedef NonlinearFactor1<VALUES, KEY> Base; ///< base class
|
||||
typedef boost::shared_ptr<GenericPrior<VALUES, KEY> > shared_ptr;
|
||||
typedef typename KEY::Value Pose; ///< shortcut to Pose type
|
||||
|
||||
Pose z_; ///< prior mean
|
||||
|
||||
/// Create generic prior
|
||||
GenericPrior(const Pose& z, const SharedNoiseModel& model, const KEY& key) :
|
||||
NonlinearFactor1<CFG, KEY>(model, key), z_(z) {
|
||||
NonlinearFactor1<VALUES, KEY>(model, key), z_(z) {
|
||||
}
|
||||
|
||||
/// Return error and optional derivative
|
||||
|
|
@ -149,11 +149,11 @@ namespace gtsam {
|
|||
/**
|
||||
* Binary factor simulating "odometry" between two Vectors
|
||||
*/
|
||||
template<class CFG = Values, class KEY = PoseKey>
|
||||
class GenericOdometry: public NonlinearFactor2<CFG, KEY, KEY> {
|
||||
template<class VALUES = Values, class KEY = PoseKey>
|
||||
class GenericOdometry: public NonlinearFactor2<VALUES, KEY, KEY> {
|
||||
public:
|
||||
typedef NonlinearFactor2<CFG, KEY, KEY> Base; ///< base class
|
||||
typedef boost::shared_ptr<GenericOdometry<CFG, KEY> > shared_ptr;
|
||||
typedef NonlinearFactor2<VALUES, KEY, KEY> Base; ///< base class
|
||||
typedef boost::shared_ptr<GenericOdometry<VALUES, KEY> > shared_ptr;
|
||||
typedef typename KEY::Value Pose; ///< shortcut to Pose type
|
||||
|
||||
Pose z_; ///< odometry measurement
|
||||
|
|
@ -161,7 +161,7 @@ namespace gtsam {
|
|||
/// Create odometry
|
||||
GenericOdometry(const Pose& z, const SharedNoiseModel& model,
|
||||
const KEY& i1, const KEY& i2) :
|
||||
NonlinearFactor2<CFG, KEY, KEY>(model, i1, i2), z_(z) {
|
||||
NonlinearFactor2<VALUES, KEY, KEY>(model, i1, i2), z_(z) {
|
||||
}
|
||||
|
||||
/// Evaluate error and optionally return derivatives
|
||||
|
|
@ -189,11 +189,11 @@ namespace gtsam {
|
|||
/**
|
||||
* Binary factor simulating "measurement" between two Vectors
|
||||
*/
|
||||
template<class CFG = Values, class XKEY = PoseKey, class LKEY = PointKey>
|
||||
class GenericMeasurement: public NonlinearFactor2<CFG, XKEY, LKEY> {
|
||||
template<class VALUES = Values, class XKEY = PoseKey, class LKEY = PointKey>
|
||||
class GenericMeasurement: public NonlinearFactor2<VALUES, XKEY, LKEY> {
|
||||
public:
|
||||
typedef NonlinearFactor2<CFG, XKEY, LKEY> Base; ///< base class
|
||||
typedef boost::shared_ptr<GenericMeasurement<CFG, XKEY, LKEY> > shared_ptr;
|
||||
typedef NonlinearFactor2<VALUES, XKEY, LKEY> Base; ///< base class
|
||||
typedef boost::shared_ptr<GenericMeasurement<VALUES, XKEY, LKEY> > shared_ptr;
|
||||
typedef typename XKEY::Value Pose; ///< shortcut to Pose type
|
||||
typedef typename LKEY::Value Point; ///< shortcut to Point type
|
||||
|
||||
|
|
@ -202,7 +202,7 @@ namespace gtsam {
|
|||
/// Create measurement factor
|
||||
GenericMeasurement(const Point& z, const SharedNoiseModel& model,
|
||||
const XKEY& i, const LKEY& j) :
|
||||
NonlinearFactor2<CFG, XKEY, LKEY>(model, i, j), z_(z) {
|
||||
NonlinearFactor2<VALUES, XKEY, LKEY>(model, i, j), z_(z) {
|
||||
}
|
||||
|
||||
/// Evaluate error and optionally return derivatives
|
||||
|
|
|
|||
|
|
@ -51,10 +51,10 @@ namespace gtsam {
|
|||
* Unary inequality constraint forcing a coordinate to be greater/less than a fixed value (c)
|
||||
* Demo implementation: should be made more general using BoundingConstraint
|
||||
*/
|
||||
template<class Cfg, class Key, unsigned int Idx>
|
||||
struct ScalarCoordConstraint1: public BoundingConstraint1<Cfg, Key> {
|
||||
typedef BoundingConstraint1<Cfg, Key> Base;
|
||||
typedef boost::shared_ptr<ScalarCoordConstraint1<Cfg, Key, Idx> > shared_ptr;
|
||||
template<class VALUES, class Key, unsigned int Idx>
|
||||
struct ScalarCoordConstraint1: public BoundingConstraint1<VALUES, Key> {
|
||||
typedef BoundingConstraint1<VALUES, Key> Base;
|
||||
typedef boost::shared_ptr<ScalarCoordConstraint1<VALUES, Key, Idx> > shared_ptr;
|
||||
|
||||
ScalarCoordConstraint1(const Key& key, double c,
|
||||
bool isGreaterThan, double mu = 1000.0) :
|
||||
|
|
@ -85,9 +85,9 @@ namespace gtsam {
|
|||
* Binary inequality constraint forcing the range between points
|
||||
* to be less than or equal to a bound
|
||||
*/
|
||||
template<class Cfg, class Key>
|
||||
struct MaxDistanceConstraint : public BoundingConstraint2<Cfg, Key, Key> {
|
||||
typedef BoundingConstraint2<Cfg, Key, Key> Base;
|
||||
template<class VALUES, class Key>
|
||||
struct MaxDistanceConstraint : public BoundingConstraint2<VALUES, Key, Key> {
|
||||
typedef BoundingConstraint2<VALUES, Key, Key> Base;
|
||||
|
||||
MaxDistanceConstraint(const Key& key1, const Key& key2, double range_bound, double mu = 1000.0)
|
||||
: Base(key1, key2, range_bound, false, mu) {}
|
||||
|
|
@ -108,9 +108,9 @@ namespace gtsam {
|
|||
* Binary inequality constraint forcing a minimum range
|
||||
* NOTE: this is not a convex function! Be careful with initialization.
|
||||
*/
|
||||
template<class Cfg, class XKey, class PKey>
|
||||
struct MinDistanceConstraint : public BoundingConstraint2<Cfg, XKey, PKey> {
|
||||
typedef BoundingConstraint2<Cfg, XKey, PKey> Base;
|
||||
template<class VALUES, class XKey, class PKey>
|
||||
struct MinDistanceConstraint : public BoundingConstraint2<VALUES, XKey, PKey> {
|
||||
typedef BoundingConstraint2<VALUES, XKey, PKey> Base;
|
||||
|
||||
MinDistanceConstraint(const XKey& key1, const PKey& key2, double range_bound, double mu = 1000.0)
|
||||
: Base(key1, key2, range_bound, true, mu) {}
|
||||
|
|
|
|||
|
|
@ -55,15 +55,15 @@ namespace gtsam {
|
|||
boost::none, boost::optional<Matrix&> H2 = boost::none);
|
||||
|
||||
/// Unary factor encoding a soft prior on a vector
|
||||
template<class CFG = Values, class Key = PoseKey>
|
||||
struct GenericPosePrior: public NonlinearFactor1<CFG, Key> {
|
||||
template<class VALUES = Values, class Key = PoseKey>
|
||||
struct GenericPosePrior: public NonlinearFactor1<VALUES, Key> {
|
||||
|
||||
Pose2 z_; ///< measurement
|
||||
|
||||
/// Create generic pose prior
|
||||
GenericPosePrior(const Pose2& z, const SharedNoiseModel& model,
|
||||
const Key& key) :
|
||||
NonlinearFactor1<CFG, Key>(model, key), z_(z) {
|
||||
NonlinearFactor1<VALUES, Key>(model, key), z_(z) {
|
||||
}
|
||||
|
||||
/// Evaluate error and optionally derivative
|
||||
|
|
@ -77,14 +77,14 @@ namespace gtsam {
|
|||
/**
|
||||
* Binary factor simulating "odometry" between two Vectors
|
||||
*/
|
||||
template<class CFG = Values, class KEY = PoseKey>
|
||||
struct GenericOdometry: public NonlinearFactor2<CFG, KEY, KEY> {
|
||||
template<class VALUES = Values, class KEY = PoseKey>
|
||||
struct GenericOdometry: public NonlinearFactor2<VALUES, KEY, KEY> {
|
||||
Pose2 z_;
|
||||
|
||||
/// Create generic odometry factor
|
||||
GenericOdometry(const Pose2& z, const SharedNoiseModel& model,
|
||||
const KEY& i1, const KEY& i2) :
|
||||
NonlinearFactor2<CFG, KEY, KEY>(model, i1, i2), z_(z) {
|
||||
NonlinearFactor2<VALUES, KEY, KEY>(model, i1, i2), z_(z) {
|
||||
}
|
||||
|
||||
/// Evaluate error and optionally derivative
|
||||
|
|
|
|||
Loading…
Reference in New Issue