From 0a3d9975f39f0e6c2c105ab73bc39f86b709c450 Mon Sep 17 00:00:00 2001 From: Duy-Nguyen Ta Date: Tue, 19 Jun 2012 06:04:31 +0000 Subject: [PATCH] adding smart flags for several static noise model creation function --- gtsam/linear/NoiseModel.cpp | 6 ++++++ gtsam/linear/NoiseModel.h | 14 +++++++------- 2 files changed, 13 insertions(+), 7 deletions(-) diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index a0901c58b..51f732db0 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -422,6 +422,12 @@ SharedDiagonal Constrained::QR(Matrix& Ab) const { /* ************************************************************************* */ // Isotropic +/* ************************************************************************* */ +Isotropic::shared_ptr Isotropic::Sigma(size_t dim, double sigma, bool smart) { + if (smart && fabs(sigma-1.0)<1e-9) return Unit::Create(dim); + return shared_ptr(new Isotropic(dim, sigma)); +} + /* ************************************************************************* */ Isotropic::shared_ptr Isotropic::Variance(size_t dim, double variance, bool smart) { if (smart && fabs(variance-1.0)<1e-9) return Unit::Create(dim); diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index f7a1c351a..b1e65feff 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -112,6 +112,8 @@ namespace gtsam { * as indeed * |y|^2 = y'*y = x'*R'*R*x * Various derived classes are available that are more efficient. + * The named constructors return a shared_ptr because, when the smart flag is true, + * the underlying object might be a derived class such as Diagonal. */ class Gaussian: public Base { @@ -274,8 +276,8 @@ namespace gtsam { * A diagonal noise model created by specifying a Vector of precisions, i.e. * i.e. the diagonal of the information matrix, i.e., weights */ - static shared_ptr Precisions(const Vector& precisions) { - return Variances(reciprocal(precisions)); + static shared_ptr Precisions(const Vector& precisions, bool smart = false) { + return Variances(reciprocal(precisions), smart); } virtual void print(const std::string& name) const; @@ -496,9 +498,7 @@ namespace gtsam { /** * An isotropic noise model created by specifying a standard devation sigma */ - static shared_ptr Sigma(size_t dim, double sigma) { - return shared_ptr(new Isotropic(dim, sigma)); - } + static shared_ptr Sigma(size_t dim, double sigma, bool smart = false); /** * An isotropic noise model created by specifying a variance = sigma^2. @@ -509,8 +509,8 @@ namespace gtsam { /** * An isotropic noise model created by specifying a precision */ - static shared_ptr Precision(size_t dim, double precision) { - return Variance(dim, 1.0/precision); + static shared_ptr Precision(size_t dim, double precision, bool smart = false) { + return Variance(dim, 1.0/precision, smart); } virtual void print(const std::string& name) const;