correct name for Welsch
parent
cdaf928ecf
commit
df8900a3d1
|
@ -197,22 +197,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 {
|
void Welsch::print(const std::string &s="") const {
|
||||||
std::cout << s << ": Welsh (" << c_ << ")" << std::endl;
|
std::cout << s << ": Welsch (" << c_ << ")" << std::endl;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool Welsh::equals(const Base &expected, double tol) const {
|
bool Welsch::equals(const Base &expected, double tol) const {
|
||||||
const Welsh* p = dynamic_cast<const Welsh*>(&expected);
|
const Welsch* p = dynamic_cast<const Welsch*>(&expected);
|
||||||
if (p == NULL) return false;
|
if (p == NULL) return false;
|
||||||
return std::abs(c_ - p->c_) < tol;
|
return std::abs(c_ - p->c_) < tol;
|
||||||
}
|
}
|
||||||
|
|
||||||
Welsh::shared_ptr Welsh::Create(double c, const ReweightScheme reweight) {
|
Welsch::shared_ptr Welsch::Create(double c, const ReweightScheme reweight) {
|
||||||
return shared_ptr(new Welsh(c, reweight));
|
return shared_ptr(new Welsch(c, reweight));
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
|
|
|
@ -238,15 +238,15 @@ namespace gtsam {
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
/// Welsh implements the "Welsh" robust error model (Zhang97ivc)
|
/// Welsch implements the "Welsch" robust error model (Zhang97ivc)
|
||||||
class GTSAM_EXPORT Welsh : public Base {
|
class GTSAM_EXPORT Welsch : public Base {
|
||||||
protected:
|
protected:
|
||||||
double c_, csquared_;
|
double c_, csquared_;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
typedef boost::shared_ptr<Welsh> shared_ptr;
|
typedef boost::shared_ptr<Welsch> shared_ptr;
|
||||||
|
|
||||||
Welsh(double c = 2.9846, const ReweightScheme reweight = Block);
|
Welsch(double c = 2.9846, const ReweightScheme reweight = Block);
|
||||||
double sqrtWeight(double error) const {
|
double sqrtWeight(double error) const {
|
||||||
double xc2 = (error*error)/csquared_;
|
double xc2 = (error*error)/csquared_;
|
||||||
return std::exp(-xc2/2.0);
|
return std::exp(-xc2/2.0);
|
||||||
|
|
Loading…
Reference in New Issue