deprecated get_noiseModel

release/4.3a0
Frank Dellaert 2019-05-16 14:40:55 -04:00
parent ac0d686c9c
commit 23f3f95ed2
6 changed files with 13 additions and 14 deletions

View File

@ -62,7 +62,7 @@ Examples: noiseModel_Gaussian, noiseModel_mEstimator_Tukey
- Casting from a base class to a derive class must be done explicitly. - Casting from a base class to a derive class must be done explicitly.
Examples: Examples:
```Python ```Python
noiseBase = factor.get_noiseModel() noiseBase = factor.noiseModel()
noiseGaussian = dynamic_cast_noiseModel_Gaussian_noiseModel_Base(noiseBase) noiseGaussian = dynamic_cast_noiseModel_Gaussian_noiseModel_Base(noiseBase)
``` ```

View File

@ -79,7 +79,7 @@ int main(const int argc, const char *argv[]) {
key2 = pose3Between->key2() - firstKey; key2 = pose3Between->key2() - firstKey;
} }
NonlinearFactor::shared_ptr simpleFactor( NonlinearFactor::shared_ptr simpleFactor(
new BetweenFactor<Pose3>(key1, key2, pose3Between->measured(), pose3Between->get_noiseModel())); new BetweenFactor<Pose3>(key1, key2, pose3Between->measured(), pose3Between->noiseModel()));
simpleGraph.add(simpleFactor); simpleGraph.add(simpleFactor);
} }
} }

View File

@ -1916,7 +1916,6 @@ virtual class NonlinearFactor {
#include <gtsam/nonlinear/NonlinearFactor.h> #include <gtsam/nonlinear/NonlinearFactor.h>
virtual class NoiseModelFactor: gtsam::NonlinearFactor { virtual class NoiseModelFactor: gtsam::NonlinearFactor {
bool equals(const gtsam::NoiseModelFactor& other, double tol) const; bool equals(const gtsam::NoiseModelFactor& other, double tol) const;
gtsam::noiseModel::Base* get_noiseModel() const; // deprecated by below
gtsam::noiseModel::Base* noiseModel() const; gtsam::noiseModel::Base* noiseModel() const;
Vector unwhitenedError(const gtsam::Values& x) const; Vector unwhitenedError(const gtsam::Values& x) const;
Vector whitenedError(const gtsam::Values& x) const; Vector whitenedError(const gtsam::Values& x) const;

View File

@ -29,14 +29,12 @@
#include <boost/serialization/base_object.hpp> #include <boost/serialization/base_object.hpp>
#include <boost/assign/list_of.hpp> #include <boost/assign/list_of.hpp>
/** #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4
* Macro to add a standard clone function to a derived factor
* @deprecated: will go away shortly - just add the clone function directly
*/
#define ADD_CLONE_NONLINEAR_FACTOR(Derived) \ #define ADD_CLONE_NONLINEAR_FACTOR(Derived) \
virtual gtsam::NonlinearFactor::shared_ptr clone() const { \ virtual gtsam::NonlinearFactor::shared_ptr clone() const { \
return boost::static_pointer_cast<gtsam::NonlinearFactor>( \ return boost::static_pointer_cast<gtsam::NonlinearFactor>( \
gtsam::NonlinearFactor::shared_ptr(new Derived(*this))); } gtsam::NonlinearFactor::shared_ptr(new Derived(*this))); }
#endif
namespace gtsam { namespace gtsam {
@ -213,11 +211,6 @@ public:
return noiseModel_; return noiseModel_;
} }
/// @deprecated access to the noise model
SharedNoiseModel get_noiseModel() const {
return noiseModel_;
}
/** /**
* Error function *without* the NoiseModel, \f$ z-h(x) \f$. * Error function *without* the NoiseModel, \f$ z-h(x) \f$.
* Override this method to finish implementing an N-way factor. * Override this method to finish implementing an N-way factor.
@ -248,6 +241,13 @@ public:
*/ */
boost::shared_ptr<GaussianFactor> linearize(const Values& x) const; boost::shared_ptr<GaussianFactor> linearize(const Values& x) const;
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4
/// @name Deprecated
/// @{
SharedNoiseModel get_noiseModel() const { return noiseModel_; }
/// @}
#endif
private: private:
/** Serialization function */ /** Serialization function */

View File

@ -153,7 +153,7 @@ public:
} }
// Whiten the system if needed // Whiten the system if needed
const SharedNoiseModel& noiseModel = this->get_noiseModel(); const SharedNoiseModel& noiseModel = this->noiseModel();
if (noiseModel && !noiseModel->isUnit()) { if (noiseModel && !noiseModel->isUnit()) {
// TODO: implement WhitenSystem for fixed size matrices and include // TODO: implement WhitenSystem for fixed size matrices and include
// above // above

View File

@ -1742,7 +1742,7 @@ virtual class NonlinearFactor {
virtual class NoiseModelFactor: gtsam::NonlinearFactor { virtual class NoiseModelFactor: gtsam::NonlinearFactor {
void equals(const gtsam::NoiseModelFactor& other, double tol) const; 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 unwhitenedError(const gtsam::Values& x) const;
Vector whitenedError(const gtsam::Values& x) const; Vector whitenedError(const gtsam::Values& x) const;
}; };