diff --git a/cython/README.md b/cython/README.md index b9ce2f012..cb23b0d4a 100644 --- a/cython/README.md +++ b/cython/README.md @@ -62,7 +62,7 @@ Examples: noiseModel_Gaussian, noiseModel_mEstimator_Tukey - Casting from a base class to a derive class must be done explicitly. Examples: ```Python - noiseBase = factor.get_noiseModel() + noiseBase = factor.noiseModel() noiseGaussian = dynamic_cast_noiseModel_Gaussian_noiseModel_Base(noiseBase) ``` diff --git a/examples/Pose3SLAMExample_changeKeys.cpp b/examples/Pose3SLAMExample_changeKeys.cpp index 9cab73822..cceaac4ee 100644 --- a/examples/Pose3SLAMExample_changeKeys.cpp +++ b/examples/Pose3SLAMExample_changeKeys.cpp @@ -79,7 +79,7 @@ int main(const int argc, const char *argv[]) { key2 = pose3Between->key2() - firstKey; } NonlinearFactor::shared_ptr simpleFactor( - new BetweenFactor(key1, key2, pose3Between->measured(), pose3Between->get_noiseModel())); + new BetweenFactor(key1, key2, pose3Between->measured(), pose3Between->noiseModel())); simpleGraph.add(simpleFactor); } } diff --git a/gtsam.h b/gtsam.h index aefe4e028..220a2c99f 100644 --- a/gtsam.h +++ b/gtsam.h @@ -1916,7 +1916,6 @@ virtual class NonlinearFactor { #include virtual class NoiseModelFactor: gtsam::NonlinearFactor { bool equals(const gtsam::NoiseModelFactor& other, double tol) const; - gtsam::noiseModel::Base* get_noiseModel() const; // deprecated by below gtsam::noiseModel::Base* noiseModel() const; Vector unwhitenedError(const gtsam::Values& x) const; Vector whitenedError(const gtsam::Values& x) const; diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index cd0dd8139..1942734c5 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -29,14 +29,12 @@ #include #include -/** - * Macro to add a standard clone function to a derived factor - * @deprecated: will go away shortly - just add the clone function directly - */ +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 #define ADD_CLONE_NONLINEAR_FACTOR(Derived) \ virtual gtsam::NonlinearFactor::shared_ptr clone() const { \ return boost::static_pointer_cast( \ gtsam::NonlinearFactor::shared_ptr(new Derived(*this))); } +#endif namespace gtsam { @@ -213,11 +211,6 @@ public: return noiseModel_; } - /// @deprecated access to the noise model - SharedNoiseModel get_noiseModel() const { - return noiseModel_; - } - /** * Error function *without* the NoiseModel, \f$ z-h(x) \f$. * Override this method to finish implementing an N-way factor. @@ -248,6 +241,13 @@ public: */ boost::shared_ptr linearize(const Values& x) const; +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 + /// @name Deprecated + /// @{ + SharedNoiseModel get_noiseModel() const { return noiseModel_; } + /// @} +#endif + private: /** Serialization function */ diff --git a/gtsam/slam/GeneralSFMFactor.h b/gtsam/slam/GeneralSFMFactor.h index 9356aceb2..0eb489f35 100644 --- a/gtsam/slam/GeneralSFMFactor.h +++ b/gtsam/slam/GeneralSFMFactor.h @@ -153,7 +153,7 @@ public: } // Whiten the system if needed - const SharedNoiseModel& noiseModel = this->get_noiseModel(); + const SharedNoiseModel& noiseModel = this->noiseModel(); if (noiseModel && !noiseModel->isUnit()) { // TODO: implement WhitenSystem for fixed size matrices and include // above diff --git a/gtsampy.h b/gtsampy.h index 27af74e74..141fca79d 100644 --- a/gtsampy.h +++ b/gtsampy.h @@ -1742,7 +1742,7 @@ virtual class NonlinearFactor { virtual class NoiseModelFactor: gtsam::NonlinearFactor { void equals(const gtsam::NoiseModelFactor& other, double tol) const; - gtsam::noiseModel::Base* get_noiseModel() const; + gtsam::noiseModel::Base* noiseModel() const; Vector unwhitenedError(const gtsam::Values& x) const; Vector whitenedError(const gtsam::Values& x) const; };