From 2f8238a9566a4ce31dba4f004e4ec3f95cde0281 Mon Sep 17 00:00:00 2001 From: Alice Anderson Date: Wed, 28 Aug 2019 17:28:10 -0700 Subject: [PATCH] Fixed spelling for Welsch and added to gtsam.h --- gtsam/linear/NoiseModel.cpp | 16 ++++++++-------- gtsam/linear/NoiseModel.h | 8 ++++---- 2 files changed, 12 insertions(+), 12 deletions(-) diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index 4d9c7883b..fac9f9ecd 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -808,22 +808,22 @@ Tukey::shared_ptr Tukey::Create(double c, const ReweightScheme reweight) { } /* ************************************************************************* */ -// Welsh +// Welsch /* ************************************************************************* */ -Welsh::Welsh(double c, const ReweightScheme reweight) : Base(reweight), c_(c), csquared_(c * c) {} +Welsch::Welsch(double c, const ReweightScheme reweight) : Base(reweight), c_(c), csquared_(c * c) {} -void Welsh::print(const std::string &s="") const { - std::cout << s << ": Welsh (" << c_ << ")" << std::endl; +void Welsch::print(const std::string &s="") const { + std::cout << s << ": Welsch (" << c_ << ")" << std::endl; } -bool Welsh::equals(const Base &expected, double tol) const { - const Welsh* p = dynamic_cast(&expected); +bool Welsch::equals(const Base &expected, double tol) const { + const Welsch* p = dynamic_cast(&expected); if (p == NULL) return false; return std::abs(c_ - p->c_) < tol; } -Welsh::shared_ptr Welsh::Create(double c, const ReweightScheme reweight) { - return shared_ptr(new Welsh(c, reweight)); +Welsch::shared_ptr Welsch::Create(double c, const ReweightScheme reweight) { + return shared_ptr(new Welsch(c, reweight)); } /* ************************************************************************* */ diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index e495921c2..347686905 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -852,15 +852,15 @@ namespace gtsam { } }; - /// Welsh implements the "Welsh" robust error model (Zhang97ivc) - class GTSAM_EXPORT Welsh : public Base { + /// Welsch implements the "Welsch" robust error model (Zhang97ivc) + class GTSAM_EXPORT Welsch : public Base { protected: double c_, csquared_; public: - typedef boost::shared_ptr shared_ptr; + typedef boost::shared_ptr shared_ptr; - Welsh(double c = 2.9846, const ReweightScheme reweight = Block); + Welsch(double c = 2.9846, const ReweightScheme reweight = Block); double weight(double error) const { double xc2 = (error*error)/csquared_; return std::exp(-xc2);