From 482d542da1d91efd592ab5fa1995f099d163c0a6 Mon Sep 17 00:00:00 2001 From: Duy-Nguyen Ta Date: Wed, 8 Mar 2017 10:31:05 -0500 Subject: [PATCH] Revert "correct name for Welsch" This reverts commit df8900a3d1383f636c24564a5ac5047788b54e64. --- gtsam/linear/MEstimators.cpp | 16 ++++++++-------- gtsam/linear/MEstimators.h | 8 ++++---- 2 files changed, 12 insertions(+), 12 deletions(-) diff --git a/gtsam/linear/MEstimators.cpp b/gtsam/linear/MEstimators.cpp index 2a8d6d99a..36fa939a6 100644 --- a/gtsam/linear/MEstimators.cpp +++ b/gtsam/linear/MEstimators.cpp @@ -197,22 +197,22 @@ Tukey::shared_ptr Tukey::Create(double c, const ReweightScheme reweight) { } /* ************************************************************************* */ -// Welsch +// Welsh /* ************************************************************************* */ -Welsch::Welsch(double c, const ReweightScheme reweight) : Base(reweight), c_(c), csquared_(c * c) {} +Welsh::Welsh(double c, const ReweightScheme reweight) : Base(reweight), c_(c), csquared_(c * c) {} -void Welsch::print(const std::string &s="") const { - std::cout << s << ": Welsch (" << c_ << ")" << std::endl; +void Welsh::print(const std::string &s="") const { + std::cout << s << ": Welsh (" << c_ << ")" << std::endl; } -bool Welsch::equals(const Base &expected, double tol) const { - const Welsch* p = dynamic_cast(&expected); +bool Welsh::equals(const Base &expected, double tol) const { + const Welsh* p = dynamic_cast(&expected); if (p == NULL) return false; return std::abs(c_ - p->c_) < tol; } -Welsch::shared_ptr Welsch::Create(double c, const ReweightScheme reweight) { - return shared_ptr(new Welsch(c, reweight)); +Welsh::shared_ptr Welsh::Create(double c, const ReweightScheme reweight) { + return shared_ptr(new Welsh(c, reweight)); } /* ************************************************************************* */ diff --git a/gtsam/linear/MEstimators.h b/gtsam/linear/MEstimators.h index 59a39a94e..77c8cee8e 100644 --- a/gtsam/linear/MEstimators.h +++ b/gtsam/linear/MEstimators.h @@ -238,15 +238,15 @@ namespace gtsam { } }; - /// Welsch implements the "Welsch" robust error model (Zhang97ivc) - class GTSAM_EXPORT Welsch : public Base { + /// Welsh implements the "Welsh" robust error model (Zhang97ivc) + class GTSAM_EXPORT Welsh : public Base { protected: double c_, csquared_; public: - typedef boost::shared_ptr shared_ptr; + typedef boost::shared_ptr shared_ptr; - Welsch(double c = 2.9846, const ReweightScheme reweight = Block); + Welsh(double c = 2.9846, const ReweightScheme reweight = Block); double sqrtWeight(double error) const { double xc2 = (error*error)/csquared_; return std::exp(-xc2/2.0);