Renamed NonlinearFactor[1-6] to NoiseModelFactor[1-6]

release/4.3a0
Richard Roberts 2012-02-20 21:52:47 +00:00
parent 3bd1aa13fc
commit 0a81c4e57a
20 changed files with 108 additions and 108 deletions

View File

@ -29,8 +29,8 @@ using namespace gtsam;
/** /**
* Unary factor for the pose. * Unary factor for the pose.
*/ */
class ResectioningFactor: public NonlinearFactor1<Pose3> { class ResectioningFactor: public NoiseModelFactor1<Pose3> {
typedef NonlinearFactor1<Pose3> Base; typedef NoiseModelFactor1<Pose3> Base;
shared_ptrK K_; // camera's intrinsic parameters shared_ptrK K_; // camera's intrinsic parameters
Point3 P_; // 3D point on the calibration rig Point3 P_; // 3D point on the calibration rig

View File

@ -46,8 +46,8 @@ namespace gtsam {
typedef boost::shared_ptr<ExtendedKalmanFilter<VALUE> > shared_ptr; typedef boost::shared_ptr<ExtendedKalmanFilter<VALUE> > shared_ptr;
typedef VALUE T; typedef VALUE T;
typedef NonlinearFactor2<VALUE, VALUE> MotionFactor; typedef NoiseModelFactor2<VALUE, VALUE> MotionFactor;
typedef NonlinearFactor1<VALUE> MeasurementFactor; typedef NoiseModelFactor1<VALUE> MeasurementFactor;
protected: protected:
T x_; // linearization point T x_; // linearization point

View File

@ -48,7 +48,7 @@ namespace gtsam {
* \nosubgrouping * \nosubgrouping
*/ */
template<class VALUE> template<class VALUE>
class NonlinearEquality: public NonlinearFactor1<VALUE> { class NonlinearEquality: public NoiseModelFactor1<VALUE> {
public: public:
typedef VALUE T; typedef VALUE T;
@ -68,7 +68,7 @@ namespace gtsam {
typedef NonlinearEquality<VALUE> This; typedef NonlinearEquality<VALUE> This;
// typedef to base class // typedef to base class
typedef NonlinearFactor1<VALUE> Base; typedef NoiseModelFactor1<VALUE> Base;
public: public:
@ -169,7 +169,7 @@ namespace gtsam {
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("NonlinearFactor1", ar & boost::serialization::make_nvp("NoiseModelFactor1",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(feasible_); ar & BOOST_SERIALIZATION_NVP(feasible_);
ar & BOOST_SERIALIZATION_NVP(allow_error_); ar & BOOST_SERIALIZATION_NVP(allow_error_);
@ -183,13 +183,13 @@ namespace gtsam {
* Simple unary equality constraint - fixes a value for a variable * Simple unary equality constraint - fixes a value for a variable
*/ */
template<class VALUE> template<class VALUE>
class NonlinearEquality1 : public NonlinearFactor1<VALUE> { class NonlinearEquality1 : public NoiseModelFactor1<VALUE> {
public: public:
typedef VALUE X; typedef VALUE X;
protected: protected:
typedef NonlinearFactor1<VALUE> Base; typedef NoiseModelFactor1<VALUE> Base;
/** default constructor to allow for serialization */ /** default constructor to allow for serialization */
NonlinearEquality1() {} NonlinearEquality1() {}
@ -230,7 +230,7 @@ namespace gtsam {
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("NonlinearFactor1", ar & boost::serialization::make_nvp("NoiseModelFactor1",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(value_); ar & BOOST_SERIALIZATION_NVP(value_);
} }
@ -242,12 +242,12 @@ namespace gtsam {
* be the same. * be the same.
*/ */
template<class VALUE> template<class VALUE>
class NonlinearEquality2 : public NonlinearFactor2<VALUE, VALUE> { class NonlinearEquality2 : public NoiseModelFactor2<VALUE, VALUE> {
public: public:
typedef VALUE X; typedef VALUE X;
protected: protected:
typedef NonlinearFactor2<VALUE, VALUE> Base; typedef NoiseModelFactor2<VALUE, VALUE> Base;
GTSAM_CONCEPT_MANIFOLD_TYPE(X); GTSAM_CONCEPT_MANIFOLD_TYPE(X);
@ -279,7 +279,7 @@ namespace gtsam {
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("NonlinearFactor2", ar & boost::serialization::make_nvp("NoiseModelFactor2",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
} }
}; // \NonlinearEquality2 }; // \NonlinearEquality2

View File

@ -294,7 +294,7 @@ private:
/** A convenient base class for creating your own NoiseModelFactor with 1 /** A convenient base class for creating your own NoiseModelFactor with 1
* variable. To derive from this class, implement evaluateError(). */ * variable. To derive from this class, implement evaluateError(). */
template<class VALUE> template<class VALUE>
class NonlinearFactor1: public NoiseModelFactor { class NoiseModelFactor1: public NoiseModelFactor {
public: public:
@ -304,14 +304,14 @@ public:
protected: protected:
typedef NoiseModelFactor Base; typedef NoiseModelFactor Base;
typedef NonlinearFactor1<VALUE> This; typedef NoiseModelFactor1<VALUE> This;
public: public:
/** Default constructor for I/O only */ /** Default constructor for I/O only */
NonlinearFactor1() {} NoiseModelFactor1() {}
virtual ~NonlinearFactor1() {} virtual ~NoiseModelFactor1() {}
inline Key key() const { return keys_[0]; } inline Key key() const { return keys_[0]; }
@ -320,7 +320,7 @@ public:
* @param z measurement * @param z measurement
* @param key by which to look up X value in Values * @param key by which to look up X value in Values
*/ */
NonlinearFactor1(const SharedNoiseModel& noiseModel, Key key1) : NoiseModelFactor1(const SharedNoiseModel& noiseModel, Key key1) :
Base(noiseModel) { Base(noiseModel) {
keys_.resize(1); keys_.resize(1);
keys_[0] = key1; keys_[0] = key1;
@ -364,14 +364,14 @@ private:
ar & boost::serialization::make_nvp("NoiseModelFactor", ar & boost::serialization::make_nvp("NoiseModelFactor",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
} }
};// \class NonlinearFactor1 };// \class NoiseModelFactor1
/* ************************************************************************* */ /* ************************************************************************* */
/** A convenient base class for creating your own NoiseModelFactor with 2 /** A convenient base class for creating your own NoiseModelFactor with 2
* variables. To derive from this class, implement evaluateError(). */ * variables. To derive from this class, implement evaluateError(). */
template<class VALUE1, class VALUE2> template<class VALUE1, class VALUE2>
class NonlinearFactor2: public NoiseModelFactor { class NoiseModelFactor2: public NoiseModelFactor {
public: public:
@ -382,28 +382,28 @@ public:
protected: protected:
typedef NoiseModelFactor Base; typedef NoiseModelFactor Base;
typedef NonlinearFactor2<VALUE1, VALUE2> This; typedef NoiseModelFactor2<VALUE1, VALUE2> This;
public: public:
/** /**
* Default Constructor for I/O * Default Constructor for I/O
*/ */
NonlinearFactor2() {} NoiseModelFactor2() {}
/** /**
* Constructor * Constructor
* @param j1 key of the first variable * @param j1 key of the first variable
* @param j2 key of the second variable * @param j2 key of the second variable
*/ */
NonlinearFactor2(const SharedNoiseModel& noiseModel, Key j1, Key j2) : NoiseModelFactor2(const SharedNoiseModel& noiseModel, Key j1, Key j2) :
Base(noiseModel) { Base(noiseModel) {
keys_.resize(2); keys_.resize(2);
keys_[0] = j1; keys_[0] = j1;
keys_[1] = j2; keys_[1] = j2;
} }
virtual ~NonlinearFactor2() {} virtual ~NoiseModelFactor2() {}
/** methods to retrieve both keys */ /** methods to retrieve both keys */
inline Key key1() const { return keys_[0]; } inline Key key1() const { return keys_[0]; }
@ -451,13 +451,13 @@ private:
ar & boost::serialization::make_nvp("NoiseModelFactor", ar & boost::serialization::make_nvp("NoiseModelFactor",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
} }
}; // \class NonlinearFactor2 }; // \class NoiseModelFactor2
/* ************************************************************************* */ /* ************************************************************************* */
/** A convenient base class for creating your own NoiseModelFactor with 3 /** A convenient base class for creating your own NoiseModelFactor with 3
* variables. To derive from this class, implement evaluateError(). */ * variables. To derive from this class, implement evaluateError(). */
template<class VALUE1, class VALUE2, class VALUE3> template<class VALUE1, class VALUE2, class VALUE3>
class NonlinearFactor3: public NoiseModelFactor { class NoiseModelFactor3: public NoiseModelFactor {
public: public:
@ -469,14 +469,14 @@ public:
protected: protected:
typedef NoiseModelFactor Base; typedef NoiseModelFactor Base;
typedef NonlinearFactor3<VALUE1, VALUE2, VALUE3> This; typedef NoiseModelFactor3<VALUE1, VALUE2, VALUE3> This;
public: public:
/** /**
* Default Constructor for I/O * Default Constructor for I/O
*/ */
NonlinearFactor3() {} NoiseModelFactor3() {}
/** /**
* Constructor * Constructor
@ -484,7 +484,7 @@ public:
* @param j2 key of the second variable * @param j2 key of the second variable
* @param j3 key of the third variable * @param j3 key of the third variable
*/ */
NonlinearFactor3(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3) : NoiseModelFactor3(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3) :
Base(noiseModel) { Base(noiseModel) {
keys_.resize(3); keys_.resize(3);
keys_[0] = j1; keys_[0] = j1;
@ -492,7 +492,7 @@ public:
keys_[2] = j3; keys_[2] = j3;
} }
virtual ~NonlinearFactor3() {} virtual ~NoiseModelFactor3() {}
/** methods to retrieve keys */ /** methods to retrieve keys */
inline Key key1() const { return keys_[0]; } inline Key key1() const { return keys_[0]; }
@ -542,13 +542,13 @@ private:
ar & boost::serialization::make_nvp("NoiseModelFactor", ar & boost::serialization::make_nvp("NoiseModelFactor",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
} }
}; // \class NonlinearFactor3 }; // \class NoiseModelFactor3
/* ************************************************************************* */ /* ************************************************************************* */
/** A convenient base class for creating your own NoiseModelFactor with 4 /** A convenient base class for creating your own NoiseModelFactor with 4
* variables. To derive from this class, implement evaluateError(). */ * variables. To derive from this class, implement evaluateError(). */
template<class VALUE1, class VALUE2, class VALUE3, class VALUE4> template<class VALUE1, class VALUE2, class VALUE3, class VALUE4>
class NonlinearFactor4: public NoiseModelFactor { class NoiseModelFactor4: public NoiseModelFactor {
public: public:
@ -561,14 +561,14 @@ public:
protected: protected:
typedef NoiseModelFactor Base; typedef NoiseModelFactor Base;
typedef NonlinearFactor4<VALUE1, VALUE2, VALUE3, VALUE4> This; typedef NoiseModelFactor4<VALUE1, VALUE2, VALUE3, VALUE4> This;
public: public:
/** /**
* Default Constructor for I/O * Default Constructor for I/O
*/ */
NonlinearFactor4() {} NoiseModelFactor4() {}
/** /**
* Constructor * Constructor
@ -577,7 +577,7 @@ public:
* @param j3 key of the third variable * @param j3 key of the third variable
* @param j4 key of the fourth variable * @param j4 key of the fourth variable
*/ */
NonlinearFactor4(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3, Key j4) : NoiseModelFactor4(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3, Key j4) :
Base(noiseModel) { Base(noiseModel) {
keys_.resize(4); keys_.resize(4);
keys_[0] = j1; keys_[0] = j1;
@ -586,7 +586,7 @@ public:
keys_[3] = j4; keys_[3] = j4;
} }
virtual ~NonlinearFactor4() {} virtual ~NoiseModelFactor4() {}
/** methods to retrieve keys */ /** methods to retrieve keys */
inline Key key1() const { return keys_[0]; } inline Key key1() const { return keys_[0]; }
@ -638,13 +638,13 @@ private:
ar & boost::serialization::make_nvp("NoiseModelFactor", ar & boost::serialization::make_nvp("NoiseModelFactor",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
} }
}; // \class NonlinearFactor4 }; // \class NoiseModelFactor4
/* ************************************************************************* */ /* ************************************************************************* */
/** A convenient base class for creating your own NoiseModelFactor with 5 /** A convenient base class for creating your own NoiseModelFactor with 5
* variables. To derive from this class, implement evaluateError(). */ * variables. To derive from this class, implement evaluateError(). */
template<class VALUE1, class VALUE2, class VALUE3, class VALUE4, class VALUE5> template<class VALUE1, class VALUE2, class VALUE3, class VALUE4, class VALUE5>
class NonlinearFactor5: public NoiseModelFactor { class NoiseModelFactor5: public NoiseModelFactor {
public: public:
@ -658,14 +658,14 @@ public:
protected: protected:
typedef NoiseModelFactor Base; typedef NoiseModelFactor Base;
typedef NonlinearFactor5<VALUE1, VALUE2, VALUE3, VALUE4, VALUE5> This; typedef NoiseModelFactor5<VALUE1, VALUE2, VALUE3, VALUE4, VALUE5> This;
public: public:
/** /**
* Default Constructor for I/O * Default Constructor for I/O
*/ */
NonlinearFactor5() {} NoiseModelFactor5() {}
/** /**
* Constructor * Constructor
@ -675,7 +675,7 @@ public:
* @param j4 key of the fourth variable * @param j4 key of the fourth variable
* @param j5 key of the fifth variable * @param j5 key of the fifth variable
*/ */
NonlinearFactor5(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3, Key j4, Key j5) : NoiseModelFactor5(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3, Key j4, Key j5) :
Base(noiseModel) { Base(noiseModel) {
keys_.resize(5); keys_.resize(5);
keys_[0] = j1; keys_[0] = j1;
@ -685,7 +685,7 @@ public:
keys_[4] = j5; keys_[4] = j5;
} }
virtual ~NonlinearFactor5() {} virtual ~NoiseModelFactor5() {}
/** methods to retrieve keys */ /** methods to retrieve keys */
inline Key key1() const { return keys_[0]; } inline Key key1() const { return keys_[0]; }
@ -740,13 +740,13 @@ private:
ar & boost::serialization::make_nvp("NoiseModelFactor", ar & boost::serialization::make_nvp("NoiseModelFactor",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
} }
}; // \class NonlinearFactor5 }; // \class NoiseModelFactor5
/* ************************************************************************* */ /* ************************************************************************* */
/** A convenient base class for creating your own NoiseModelFactor with 6 /** A convenient base class for creating your own NoiseModelFactor with 6
* variables. To derive from this class, implement evaluateError(). */ * variables. To derive from this class, implement evaluateError(). */
template<class VALUE1, class VALUE2, class VALUE3, class VALUE4, class VALUE5, class VALUE6> template<class VALUE1, class VALUE2, class VALUE3, class VALUE4, class VALUE5, class VALUE6>
class NonlinearFactor6: public NoiseModelFactor { class NoiseModelFactor6: public NoiseModelFactor {
public: public:
@ -761,14 +761,14 @@ public:
protected: protected:
typedef NoiseModelFactor Base; typedef NoiseModelFactor Base;
typedef NonlinearFactor6<VALUE1, VALUE2, VALUE3, VALUE4, VALUE5, VALUE6> This; typedef NoiseModelFactor6<VALUE1, VALUE2, VALUE3, VALUE4, VALUE5, VALUE6> This;
public: public:
/** /**
* Default Constructor for I/O * Default Constructor for I/O
*/ */
NonlinearFactor6() {} NoiseModelFactor6() {}
/** /**
* Constructor * Constructor
@ -779,7 +779,7 @@ public:
* @param j5 key of the fifth variable * @param j5 key of the fifth variable
* @param j6 key of the fifth variable * @param j6 key of the fifth variable
*/ */
NonlinearFactor6(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3, Key j4, Key j5, Key j6) : NoiseModelFactor6(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3, Key j4, Key j5, Key j6) :
Base(noiseModel) { Base(noiseModel) {
keys_.resize(6); keys_.resize(6);
keys_[0] = j1; keys_[0] = j1;
@ -790,7 +790,7 @@ public:
keys_[5] = j6; keys_[5] = j6;
} }
virtual ~NonlinearFactor6() {} virtual ~NoiseModelFactor6() {}
/** methods to retrieve keys */ /** methods to retrieve keys */
inline Key key1() const { return keys_[0]; } inline Key key1() const { return keys_[0]; }
@ -848,7 +848,7 @@ private:
ar & boost::serialization::make_nvp("NoiseModelFactor", ar & boost::serialization::make_nvp("NoiseModelFactor",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
} }
}; // \class NonlinearFactor6 }; // \class NoiseModelFactor6
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -26,7 +26,7 @@ namespace gtsam {
* Binary factor for a bearing measurement * Binary factor for a bearing measurement
*/ */
template<class POSE, class POINT> template<class POSE, class POINT>
class BearingFactor: public NonlinearFactor2<POSE, POINT> { class BearingFactor: public NoiseModelFactor2<POSE, POINT> {
private: private:
typedef POSE Pose; typedef POSE Pose;
@ -34,7 +34,7 @@ namespace gtsam {
typedef POINT Point; typedef POINT Point;
typedef BearingFactor<POSE, POINT> This; typedef BearingFactor<POSE, POINT> This;
typedef NonlinearFactor2<POSE, POINT> Base; typedef NoiseModelFactor2<POSE, POINT> Base;
Rot measured_; /** measurement */ Rot measured_; /** measurement */
@ -79,7 +79,7 @@ namespace gtsam {
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("NonlinearFactor2", ar & boost::serialization::make_nvp("NoiseModelFactor2",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(measured_);
} }

View File

@ -28,7 +28,7 @@ namespace gtsam {
* Binary factor for a bearing measurement * Binary factor for a bearing measurement
*/ */
template<class POSE, class POINT> template<class POSE, class POINT>
class BearingRangeFactor: public NonlinearFactor2<POSE, POINT> { class BearingRangeFactor: public NoiseModelFactor2<POSE, POINT> {
private: private:
typedef POSE Pose; typedef POSE Pose;
@ -36,7 +36,7 @@ namespace gtsam {
typedef POINT Point; typedef POINT Point;
typedef BearingRangeFactor<POSE, POINT> This; typedef BearingRangeFactor<POSE, POINT> This;
typedef NonlinearFactor2<POSE, POINT> Base; typedef NoiseModelFactor2<POSE, POINT> Base;
// the measurement // the measurement
Rot measuredBearing_; Rot measuredBearing_;
@ -106,7 +106,7 @@ namespace gtsam {
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("NonlinearFactor2", ar & boost::serialization::make_nvp("NoiseModelFactor2",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(measuredBearing_); ar & BOOST_SERIALIZATION_NVP(measuredBearing_);
ar & BOOST_SERIALIZATION_NVP(measuredRange_); ar & BOOST_SERIALIZATION_NVP(measuredRange_);

View File

@ -29,7 +29,7 @@ namespace gtsam {
* @tparam VALUE the Value type * @tparam VALUE the Value type
*/ */
template<class VALUE> template<class VALUE>
class BetweenFactor: public NonlinearFactor2<VALUE, VALUE> { class BetweenFactor: public NoiseModelFactor2<VALUE, VALUE> {
public: public:
@ -38,7 +38,7 @@ namespace gtsam {
private: private:
typedef BetweenFactor<VALUE> This; typedef BetweenFactor<VALUE> This;
typedef NonlinearFactor2<VALUE, VALUE> Base; typedef NoiseModelFactor2<VALUE, VALUE> Base;
VALUE measured_; /** The measurement */ VALUE measured_; /** The measurement */
@ -106,7 +106,7 @@ namespace gtsam {
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("NonlinearFactor2", ar & boost::serialization::make_nvp("NoiseModelFactor2",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(measured_);
} }

View File

@ -29,9 +29,9 @@ namespace gtsam {
* a scalar for comparison. * a scalar for comparison.
*/ */
template<class VALUE> template<class VALUE>
struct BoundingConstraint1: public NonlinearFactor1<VALUE> { struct BoundingConstraint1: public NoiseModelFactor1<VALUE> {
typedef VALUE X; typedef VALUE X;
typedef NonlinearFactor1<VALUE> Base; typedef NoiseModelFactor1<VALUE> Base;
typedef boost::shared_ptr<BoundingConstraint1<VALUE> > shared_ptr; typedef boost::shared_ptr<BoundingConstraint1<VALUE> > shared_ptr;
double threshold_; double threshold_;
@ -84,7 +84,7 @@ private:
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("NonlinearFactor1", ar & boost::serialization::make_nvp("NoiseModelFactor1",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(threshold_); ar & BOOST_SERIALIZATION_NVP(threshold_);
ar & BOOST_SERIALIZATION_NVP(isGreaterThan_); ar & BOOST_SERIALIZATION_NVP(isGreaterThan_);
@ -96,11 +96,11 @@ private:
* to implement for specific systems * to implement for specific systems
*/ */
template<class VALUE1, class VALUE2> template<class VALUE1, class VALUE2>
struct BoundingConstraint2: public NonlinearFactor2<VALUE1, VALUE2> { struct BoundingConstraint2: public NoiseModelFactor2<VALUE1, VALUE2> {
typedef VALUE1 X1; typedef VALUE1 X1;
typedef VALUE2 X2; typedef VALUE2 X2;
typedef NonlinearFactor2<VALUE1, VALUE2> Base; typedef NoiseModelFactor2<VALUE1, VALUE2> Base;
typedef boost::shared_ptr<BoundingConstraint2<VALUE1, VALUE2> > shared_ptr; typedef boost::shared_ptr<BoundingConstraint2<VALUE1, VALUE2> > shared_ptr;
double threshold_; double threshold_;
@ -157,7 +157,7 @@ private:
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("NonlinearFactor2", ar & boost::serialization::make_nvp("NoiseModelFactor2",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(threshold_); ar & BOOST_SERIALIZATION_NVP(threshold_);
ar & BOOST_SERIALIZATION_NVP(isGreaterThan_); ar & BOOST_SERIALIZATION_NVP(isGreaterThan_);

View File

@ -31,7 +31,7 @@ namespace gtsam {
*/ */
template <class CAMERA, class LANDMARK> template <class CAMERA, class LANDMARK>
class GeneralSFMFactor: class GeneralSFMFactor:
public NonlinearFactor2<CAMERA, LANDMARK> { public NoiseModelFactor2<CAMERA, LANDMARK> {
protected: protected:
Point2 measured_; ///< the 2D measurement Point2 measured_; ///< the 2D measurement
@ -39,7 +39,7 @@ namespace gtsam {
typedef CAMERA Cam; ///< typedef for camera type typedef CAMERA Cam; ///< typedef for camera type
typedef GeneralSFMFactor<CAMERA, LANDMARK> This; ///< typedef for this object typedef GeneralSFMFactor<CAMERA, LANDMARK> This; ///< typedef for this object
typedef NonlinearFactor2<CAMERA, LANDMARK> Base; ///< typedef for the base class typedef NoiseModelFactor2<CAMERA, LANDMARK> Base; ///< typedef for the base class
typedef Point2 Measurement; ///< typedef for the measurement typedef Point2 Measurement; ///< typedef for the measurement
// shorthand for a smart pointer to a factor // shorthand for a smart pointer to a factor

View File

@ -39,14 +39,14 @@ namespace gtsam {
* construct the mask. * construct the mask.
*/ */
template<class VALUE> template<class VALUE>
class PartialPriorFactor: public NonlinearFactor1<VALUE> { class PartialPriorFactor: public NoiseModelFactor1<VALUE> {
public: public:
typedef VALUE T; typedef VALUE T;
protected: protected:
typedef NonlinearFactor1<VALUE> Base; typedef NoiseModelFactor1<VALUE> Base;
typedef PartialPriorFactor<VALUE> This; typedef PartialPriorFactor<VALUE> This;
Vector prior_; ///< measurement on logmap parameters, in compressed form Vector prior_; ///< measurement on logmap parameters, in compressed form
@ -133,7 +133,7 @@ namespace gtsam {
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("NonlinearFactor1", ar & boost::serialization::make_nvp("NoiseModelFactor1",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(prior_); ar & BOOST_SERIALIZATION_NVP(prior_);
ar & BOOST_SERIALIZATION_NVP(mask_); ar & BOOST_SERIALIZATION_NVP(mask_);

View File

@ -24,14 +24,14 @@ namespace gtsam {
* A class for a soft prior on any Value type * A class for a soft prior on any Value type
*/ */
template<class VALUE> template<class VALUE>
class PriorFactor: public NonlinearFactor1<VALUE> { class PriorFactor: public NoiseModelFactor1<VALUE> {
public: public:
typedef VALUE T; typedef VALUE T;
private: private:
typedef NonlinearFactor1<VALUE> Base; typedef NoiseModelFactor1<VALUE> Base;
VALUE prior_; /** The measurement */ VALUE prior_; /** The measurement */
@ -86,7 +86,7 @@ namespace gtsam {
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("NonlinearFactor1", ar & boost::serialization::make_nvp("NoiseModelFactor1",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(prior_); ar & BOOST_SERIALIZATION_NVP(prior_);
} }

View File

@ -30,7 +30,7 @@ namespace gtsam {
* i.e. the main building block for visual SLAM. * i.e. the main building block for visual SLAM.
*/ */
template<class POSE, class LANDMARK> template<class POSE, class LANDMARK>
class GenericProjectionFactor: public NonlinearFactor2<POSE, LANDMARK> { class GenericProjectionFactor: public NoiseModelFactor2<POSE, LANDMARK> {
protected: protected:
// Keep a copy of measurement and calibration for I/O // Keep a copy of measurement and calibration for I/O
@ -40,7 +40,7 @@ namespace gtsam {
public: public:
/// shorthand for base class type /// shorthand for base class type
typedef NonlinearFactor2<POSE, LANDMARK> Base; typedef NoiseModelFactor2<POSE, LANDMARK> Base;
/// shorthand for this class /// shorthand for this class
typedef GenericProjectionFactor<POSE, LANDMARK> This; typedef GenericProjectionFactor<POSE, LANDMARK> This;

View File

@ -26,13 +26,13 @@ namespace gtsam {
* Binary factor for a range measurement * Binary factor for a range measurement
*/ */
template<class POSE, class POINT> template<class POSE, class POINT>
class RangeFactor: public NonlinearFactor2<POSE, POINT> { class RangeFactor: public NoiseModelFactor2<POSE, POINT> {
private: private:
double measured_; /** measurement */ double measured_; /** measurement */
typedef RangeFactor<POSE, POINT> This; typedef RangeFactor<POSE, POINT> This;
typedef NonlinearFactor2<POSE, POINT> Base; typedef NoiseModelFactor2<POSE, POINT> Base;
typedef POSE Pose; typedef POSE Pose;
typedef POINT Point; typedef POINT Point;
@ -79,7 +79,7 @@ namespace gtsam {
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("NonlinearFactor2", ar & boost::serialization::make_nvp("NoiseModelFactor2",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(measured_);
} }

View File

@ -23,7 +23,7 @@
namespace gtsam { namespace gtsam {
template<class POSE, class LANDMARK> template<class POSE, class LANDMARK>
class GenericStereoFactor: public NonlinearFactor2<POSE, LANDMARK> { class GenericStereoFactor: public NoiseModelFactor2<POSE, LANDMARK> {
private: private:
// Keep a copy of measurement and calibration for I/O // Keep a copy of measurement and calibration for I/O
@ -33,7 +33,7 @@ private:
public: public:
// shorthand for base class type // shorthand for base class type
typedef NonlinearFactor2<POSE, LANDMARK> Base; ///< typedef for base class typedef NoiseModelFactor2<POSE, LANDMARK> Base; ///< typedef for base class
typedef boost::shared_ptr<GenericStereoFactor> shared_ptr; ///< typedef for shared pointer to this object typedef boost::shared_ptr<GenericStereoFactor> shared_ptr; ///< typedef for shared pointer to this object
typedef POSE CamPose; ///< typedef for Pose Lie Value type typedef POSE CamPose; ///< typedef for Pose Lie Value type

View File

@ -120,9 +120,9 @@ namespace simulated2D {
* Unary factor encoding a soft prior on a vector * Unary factor encoding a soft prior on a vector
*/ */
template<class VALUE = Point2> template<class VALUE = Point2>
class GenericPrior: public NonlinearFactor1<VALUE> { class GenericPrior: public NoiseModelFactor1<VALUE> {
public: public:
typedef NonlinearFactor1<VALUE> Base; ///< base class typedef NoiseModelFactor1<VALUE> Base; ///< base class
typedef boost::shared_ptr<GenericPrior<VALUE> > shared_ptr; typedef boost::shared_ptr<GenericPrior<VALUE> > shared_ptr;
typedef VALUE Pose; ///< shortcut to Pose type typedef VALUE Pose; ///< shortcut to Pose type
@ -157,9 +157,9 @@ namespace simulated2D {
* Binary factor simulating "odometry" between two Vectors * Binary factor simulating "odometry" between two Vectors
*/ */
template<class VALUE = Point2> template<class VALUE = Point2>
class GenericOdometry: public NonlinearFactor2<VALUE, VALUE> { class GenericOdometry: public NoiseModelFactor2<VALUE, VALUE> {
public: public:
typedef NonlinearFactor2<VALUE, VALUE> Base; ///< base class typedef NoiseModelFactor2<VALUE, VALUE> Base; ///< base class
typedef boost::shared_ptr<GenericOdometry<VALUE> > shared_ptr; typedef boost::shared_ptr<GenericOdometry<VALUE> > shared_ptr;
typedef VALUE Pose; ///< shortcut to Pose type typedef VALUE Pose; ///< shortcut to Pose type
@ -196,9 +196,9 @@ namespace simulated2D {
* Binary factor simulating "measurement" between two Vectors * Binary factor simulating "measurement" between two Vectors
*/ */
template<class POSE, class LANDMARK> template<class POSE, class LANDMARK>
class GenericMeasurement: public NonlinearFactor2<POSE, LANDMARK> { class GenericMeasurement: public NoiseModelFactor2<POSE, LANDMARK> {
public: public:
typedef NonlinearFactor2<POSE, LANDMARK> Base; ///< base class typedef NoiseModelFactor2<POSE, LANDMARK> Base; ///< base class
typedef boost::shared_ptr<GenericMeasurement<POSE, LANDMARK> > shared_ptr; typedef boost::shared_ptr<GenericMeasurement<POSE, LANDMARK> > shared_ptr;
typedef POSE Pose; ///< shortcut to Pose type typedef POSE Pose; ///< shortcut to Pose type
typedef LANDMARK Landmark; ///< shortcut to Landmark type typedef LANDMARK Landmark; ///< shortcut to Landmark type

View File

@ -78,13 +78,13 @@ namespace simulated2DOriented {
/// Unary factor encoding a soft prior on a vector /// Unary factor encoding a soft prior on a vector
template<class VALUE = Pose2> template<class VALUE = Pose2>
struct GenericPosePrior: public NonlinearFactor1<VALUE> { struct GenericPosePrior: public NoiseModelFactor1<VALUE> {
Pose2 measured_; ///< measurement Pose2 measured_; ///< measurement
/// Create generic pose prior /// Create generic pose prior
GenericPosePrior(const Pose2& measured, const SharedNoiseModel& model, Key key) : GenericPosePrior(const Pose2& measured, const SharedNoiseModel& model, Key key) :
NonlinearFactor1<VALUE>(model, key), measured_(measured) { NoiseModelFactor1<VALUE>(model, key), measured_(measured) {
} }
/// Evaluate error and optionally derivative /// Evaluate error and optionally derivative
@ -99,7 +99,7 @@ namespace simulated2DOriented {
* Binary factor simulating "odometry" between two Vectors * Binary factor simulating "odometry" between two Vectors
*/ */
template<class VALUE = Pose2> template<class VALUE = Pose2>
struct GenericOdometry: public NonlinearFactor2<VALUE, VALUE> { struct GenericOdometry: public NoiseModelFactor2<VALUE, VALUE> {
Pose2 measured_; ///< Between measurement for odometry factor Pose2 measured_; ///< Between measurement for odometry factor
/** /**
@ -107,7 +107,7 @@ namespace simulated2DOriented {
*/ */
GenericOdometry(const Pose2& measured, const SharedNoiseModel& model, GenericOdometry(const Pose2& measured, const SharedNoiseModel& model,
Key i1, Key i2) : Key i1, Key i2) :
NonlinearFactor2<VALUE, VALUE>(model, i1, i2), measured_(measured) { NoiseModelFactor2<VALUE, VALUE>(model, i1, i2), measured_(measured) {
} }
/// Evaluate error and optionally derivative /// Evaluate error and optionally derivative

View File

@ -64,7 +64,7 @@ Point3 mea(const Point3& x, const Point3& l,
/** /**
* A prior factor on a single linear robot pose * A prior factor on a single linear robot pose
*/ */
struct PointPrior3D: public NonlinearFactor1<Point3> { struct PointPrior3D: public NoiseModelFactor1<Point3> {
Point3 measured_; ///< The prior pose value for the variable attached to this factor Point3 measured_; ///< The prior pose value for the variable attached to this factor
@ -75,7 +75,7 @@ struct PointPrior3D: public NonlinearFactor1<Point3> {
* @param key is the key for the pose * @param key is the key for the pose
*/ */
PointPrior3D(const Point3& measured, const SharedNoiseModel& model, Key key) : PointPrior3D(const Point3& measured, const SharedNoiseModel& model, Key key) :
NonlinearFactor1<Point3> (model, key), measured_(measured) { NoiseModelFactor1<Point3> (model, key), measured_(measured) {
} }
/** /**
@ -94,7 +94,7 @@ struct PointPrior3D: public NonlinearFactor1<Point3> {
/** /**
* Models a linear 3D measurement between 3D points * Models a linear 3D measurement between 3D points
*/ */
struct Simulated3DMeasurement: public NonlinearFactor2<Point3, Point3> { struct Simulated3DMeasurement: public NoiseModelFactor2<Point3, Point3> {
Point3 measured_; ///< Linear displacement between a pose and landmark Point3 measured_; ///< Linear displacement between a pose and landmark
@ -107,7 +107,7 @@ struct Simulated3DMeasurement: public NonlinearFactor2<Point3, Point3> {
*/ */
Simulated3DMeasurement(const Point3& measured, const SharedNoiseModel& model, Simulated3DMeasurement(const Point3& measured, const SharedNoiseModel& model,
Key poseKey, Key pointKey) : Key poseKey, Key pointKey) :
NonlinearFactor2<Point3, Point3>(model, poseKey, pointKey), measured_(measured) {} NoiseModelFactor2<Point3, Point3>(model, poseKey, pointKey), measured_(measured) {}
/** /**
* Error function with optional derivatives * Error function with optional derivatives

View File

@ -198,12 +198,12 @@ namespace example {
0.0, cos(v.y())); 0.0, cos(v.y()));
} }
struct UnaryFactor: public gtsam::NonlinearFactor1<Point2> { struct UnaryFactor: public gtsam::NoiseModelFactor1<Point2> {
Point2 z_; Point2 z_;
UnaryFactor(const Point2& z, const SharedNoiseModel& model, Key key) : UnaryFactor(const Point2& z, const SharedNoiseModel& model, Key key) :
gtsam::NonlinearFactor1<Point2>(model, key), z_(z) { gtsam::NoiseModelFactor1<Point2>(model, key), z_(z) {
} }
Vector evaluateError(const Point2& x, boost::optional<Matrix&> A = boost::none) const { Vector evaluateError(const Point2& x, boost::optional<Matrix&> A = boost::none) const {

View File

@ -88,12 +88,12 @@ TEST( ExtendedKalmanFilter, linear ) {
// Create Motion Model Factor // Create Motion Model Factor
class NonlinearMotionModel : public NonlinearFactor2<Point2,Point2> { class NonlinearMotionModel : public NoiseModelFactor2<Point2,Point2> {
public: public:
typedef Point2 T; typedef Point2 T;
private: private:
typedef NonlinearFactor2<Point2, Point2> Base; typedef NoiseModelFactor2<Point2, Point2> Base;
typedef NonlinearMotionModel This; typedef NonlinearMotionModel This;
protected: protected:
@ -235,13 +235,13 @@ public:
}; };
// Create Measurement Model Factor // Create Measurement Model Factor
class NonlinearMeasurementModel : public NonlinearFactor1<Point2> { class NonlinearMeasurementModel : public NoiseModelFactor1<Point2> {
public: public:
typedef Point2 T; typedef Point2 T;
private: private:
typedef NonlinearFactor1<Point2> Base; typedef NoiseModelFactor1<Point2> Base;
typedef NonlinearMeasurementModel This; typedef NonlinearMeasurementModel This;
protected: protected:

View File

@ -238,9 +238,9 @@ TEST( NonlinearFactor, linearize_constraint2 )
} }
/* ************************************************************************* */ /* ************************************************************************* */
class TestFactor4 : public NonlinearFactor4<LieVector, LieVector, LieVector, LieVector> { class TestFactor4 : public NoiseModelFactor4<LieVector, LieVector, LieVector, LieVector> {
public: public:
typedef NonlinearFactor4<LieVector, LieVector, LieVector, LieVector> Base; typedef NoiseModeFactor4<LieVector, LieVector, LieVector, LieVector> Base;
TestFactor4() : Base(sharedSigmas(Vector_(1, 2.0)), "x1", "x2", "x3", "x4") {} TestFactor4() : Base(sharedSigmas(Vector_(1, 2.0)), "x1", "x2", "x3", "x4") {}
virtual Vector virtual Vector
@ -260,7 +260,7 @@ public:
}; };
/* ************************************ */ /* ************************************ */
TEST(NonlinearFactor, NonlinearFactor4) { TEST(NonlinearFactor, NoiseModelFactor4) {
TestFactor4 tf; TestFactor4 tf;
Values tv; Values tv;
tv.insert("x1", LieVector(1, 1.0)); tv.insert("x1", LieVector(1, 1.0));
@ -283,9 +283,9 @@ TEST(NonlinearFactor, NonlinearFactor4) {
} }
/* ************************************************************************* */ /* ************************************************************************* */
class TestFactor5 : public NonlinearFactor5<LieVector, LieVector, LieVector, LieVector, LieVector> { class TestFactor5 : public NoiseModelFactor5<LieVector, LieVector, LieVector, LieVector, LieVector> {
public: public:
typedef NonlinearFactor5<LieVector, LieVector, LieVector, LieVector, LieVector> Base; typedef NoiseModelFactor5<LieVector, LieVector, LieVector, LieVector, LieVector> Base;
TestFactor5() : Base(sharedSigmas(Vector_(1, 2.0)), "x1", "x2", "x3", "x4", "x5") {} TestFactor5() : Base(sharedSigmas(Vector_(1, 2.0)), "x1", "x2", "x3", "x4", "x5") {}
virtual Vector virtual Vector
@ -307,7 +307,7 @@ public:
}; };
/* ************************************ */ /* ************************************ */
TEST(NonlinearFactor, NonlinearFactor5) { TEST(NonlinearFactor, NoiseModelFactor5) {
TestFactor5 tf; TestFactor5 tf;
Values tv; Values tv;
tv.insert("x1", LieVector(1, 1.0)); tv.insert("x1", LieVector(1, 1.0));
@ -333,9 +333,9 @@ TEST(NonlinearFactor, NonlinearFactor5) {
} }
/* ************************************************************************* */ /* ************************************************************************* */
class TestFactor6 : public NonlinearFactor6<LieVector, LieVector, LieVector, LieVector, LieVector, LieVector> { class TestFactor6 : public NoiseModelFactor6<LieVector, LieVector, LieVector, LieVector, LieVector, LieVector> {
public: public:
typedef NonlinearFactor6<LieVector, LieVector, LieVector, LieVector, LieVector, LieVector> Base; typedef NoiseModelFactor6<LieVector, LieVector, LieVector, LieVector, LieVector, LieVector> Base;
TestFactor6() : Base(sharedSigmas(Vector_(1, 2.0)), "x1", "x2", "x3", "x4", "x5", "x6") {} TestFactor6() : Base(sharedSigmas(Vector_(1, 2.0)), "x1", "x2", "x3", "x4", "x5", "x6") {}
virtual Vector virtual Vector
@ -359,7 +359,7 @@ public:
}; };
/* ************************************ */ /* ************************************ */
TEST(NonlinearFactor, NonlinearFactor6) { TEST(NonlinearFactor, NoiseModelFactor6) {
TestFactor6 tf; TestFactor6 tf;
Values tv; Values tv;
tv.insert("x1", LieVector(1, 1.0)); tv.insert("x1", LieVector(1, 1.0));