Skip to content

Commit

Permalink
Revert "renamed residual to loss, follow PR #188"
Browse files Browse the repository at this point in the history
This reverts commit 4e3542a.
  • Loading branch information
yetongumich authored and akshay-krishnan committed May 3, 2020
1 parent cdc6911 commit 886b874
Show file tree
Hide file tree
Showing 6 changed files with 68 additions and 71 deletions.
18 changes: 9 additions & 9 deletions gtsam.h
Original file line number Diff line number Diff line change
Expand Up @@ -1458,7 +1458,7 @@ virtual class Null: gtsam::noiseModel::mEstimator::Base {
void serializable() const;

double weight(double error) const;
double loss(double error) const;
double residual(double error) const;
};

virtual class Fair: gtsam::noiseModel::mEstimator::Base {
Expand All @@ -1469,7 +1469,7 @@ virtual class Fair: gtsam::noiseModel::mEstimator::Base {
void serializable() const;

double weight(double error) const;
double loss(double error) const;
double residual(double error) const;
};

virtual class Huber: gtsam::noiseModel::mEstimator::Base {
Expand All @@ -1480,7 +1480,7 @@ virtual class Huber: gtsam::noiseModel::mEstimator::Base {
void serializable() const;

double weight(double error) const;
double loss(double error) const;
double residual(double error) const;
};

virtual class Cauchy: gtsam::noiseModel::mEstimator::Base {
Expand All @@ -1491,7 +1491,7 @@ virtual class Cauchy: gtsam::noiseModel::mEstimator::Base {
void serializable() const;

double weight(double error) const;
double loss(double error) const;
double residual(double error) const;
};

virtual class Tukey: gtsam::noiseModel::mEstimator::Base {
Expand All @@ -1502,7 +1502,7 @@ virtual class Tukey: gtsam::noiseModel::mEstimator::Base {
void serializable() const;

double weight(double error) const;
double loss(double error) const;
double residual(double error) const;
};

virtual class Welsch: gtsam::noiseModel::mEstimator::Base {
Expand All @@ -1513,7 +1513,7 @@ virtual class Welsch: gtsam::noiseModel::mEstimator::Base {
void serializable() const;

double weight(double error) const;
double loss(double error) const;
double residual(double error) const;
};

virtual class GemanMcClure: gtsam::noiseModel::mEstimator::Base {
Expand All @@ -1524,7 +1524,7 @@ virtual class GemanMcClure: gtsam::noiseModel::mEstimator::Base {
void serializable() const;

double weight(double error) const;
double loss(double error) const;
double residual(double error) const;
};

virtual class DCS: gtsam::noiseModel::mEstimator::Base {
Expand All @@ -1535,7 +1535,7 @@ virtual class DCS: gtsam::noiseModel::mEstimator::Base {
void serializable() const;

double weight(double error) const;
double loss(double error) const;
double residual(double error) const;
};

virtual class L2WithDeadZone: gtsam::noiseModel::mEstimator::Base {
Expand All @@ -1546,7 +1546,7 @@ virtual class L2WithDeadZone: gtsam::noiseModel::mEstimator::Base {
void serializable() const;

double weight(double error) const;
double loss(double error) const;
double residual(double error) const;
};

}///\namespace mEstimator
Expand Down
16 changes: 8 additions & 8 deletions gtsam/linear/LossFunctions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,7 @@ double Fair::weight(double error) const {
return 1.0 / (1.0 + std::abs(error) / c_);
}

double Fair::loss(double error) const {
double Fair::residual(double error) const {
const double absError = std::abs(error);
const double normalizedError = absError / c_;
const double c_2 = c_ * c_;
Expand Down Expand Up @@ -175,7 +175,7 @@ double Huber::weight(double error) const {
return (absError <= k_) ? (1.0) : (k_ / absError);
}

double Huber::loss(double error) const {
double Huber::residual(double error) const {
const double absError = std::abs(error);
if (absError <= k_) { // |x| <= k
return error*error / 2;
Expand Down Expand Up @@ -212,7 +212,7 @@ double Cauchy::weight(double error) const {
return ksquared_ / (ksquared_ + error*error);
}

double Cauchy::loss(double error) const {
double Cauchy::residual(double error) const {
const double val = std::log1p(error * error / ksquared_);
return ksquared_ * val * 0.5;
}
Expand Down Expand Up @@ -249,7 +249,7 @@ double Tukey::weight(double error) const {
return 0.0;
}

double Tukey::loss(double error) const {
double Tukey::residual(double error) const {
double absError = std::abs(error);
if (absError <= c_) {
const double one_minus_xc2 = 1.0 - error*error/csquared_;
Expand Down Expand Up @@ -285,7 +285,7 @@ double Welsch::weight(double error) const {
return std::exp(-xc2);
}

double Welsch::loss(double error) const {
double Welsch::residual(double error) const {
const double xc2 = (error*error)/csquared_;
return csquared_ * 0.5 * -std::expm1(-xc2);
}
Expand Down Expand Up @@ -318,7 +318,7 @@ double GemanMcClure::weight(double error) const {
return c4/(c2error*c2error);
}

double GemanMcClure::loss(double error) const {
double GemanMcClure::residual(double error) const {
const double c2 = c_*c_;
const double error2 = error*error;
return 0.5 * (c2 * error2) / (c2 + error2);
Expand Down Expand Up @@ -356,7 +356,7 @@ double DCS::weight(double error) const {
return 1.0;
}

double DCS::loss(double error) const {
double DCS::residual(double error) const {
// This is the simplified version of Eq 9 from (Agarwal13icra)
// after you simplify and cancel terms.
const double e2 = error*error;
Expand Down Expand Up @@ -400,7 +400,7 @@ double L2WithDeadZone::weight(double error) const {
else return (k_+error)/error;
}

double L2WithDeadZone::loss(double error) const {
double L2WithDeadZone::residual(double error) const {
const double abs_error = std::abs(error);
return (abs_error < k_) ? 0.0 : 0.5*(k_-abs_error)*(k_-abs_error);
}
Expand Down
33 changes: 15 additions & 18 deletions gtsam/linear/LossFunctions.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,12 +36,12 @@ namespace noiseModel {
* The mEstimator name space contains all robust error functions.
* It mirrors the exposition at
* https://members.loria.fr/MOBerger/Enseignement/Master2/Documents/ZhangIVC-97-01.pdf
* which talks about minimizing \sum \rho(r_i), where \rho is a loss function of choice.
* which talks about minimizing \sum \rho(r_i), where \rho is a residual function of choice.
*
* To illustrate, let's consider the least-squares (L2), L1, and Huber estimators as examples:
*
* Name Symbol Least-Squares L1-norm Huber
* Loss \rho(x) 0.5*x^2 |x| 0.5*x^2 if |x|<k, 0.5*k^2 + k|x-k| otherwise
* Residual \rho(x) 0.5*x^2 |x| 0.5*x^2 if |x|<k, 0.5*k^2 + k|x-k| otherwise
* Derivative \phi(x) x sgn(x) x if |x|<k, k sgn(x) otherwise
* Weight w(x)=\phi(x)/x 1 1/|x| 1 if |x|<k, k/|x| otherwise
*
Expand Down Expand Up @@ -75,20 +75,17 @@ class GTSAM_EXPORT Base {
* the quadratic function for an L2 penalty, the absolute value function for
* an L1 penalty, etc.
*
* TODO(mikebosse): When the loss function has as input the norm of the
* TODO(mikebosse): When the residual function has as input the norm of the
* residual vector, then it prevents implementations of asymmeric loss
* functions. It would be better for this function to accept the vector and
* internally call the norm if necessary.
*/
virtual double loss(double error) const { return 0; };
virtual double residual(double error) const { return 0; };

#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4
virtual double residual(double error) const { return loss(error); };
#endif
/*
* This method is responsible for returning the weight function for a given
* amount of error. The weight function is related to the analytic derivative
* of the loss function. See
* of the residual function. See
* https://members.loria.fr/MOBerger/Enseignement/Master2/Documents/ZhangIVC-97-01.pdf
* for details. This method is required when optimizing cost functions with
* robust penalties using iteratively re-weighted least squares.
Expand Down Expand Up @@ -126,15 +123,15 @@ class GTSAM_EXPORT Base {
}
};

/// Null class is the L2 norm and not robust; equivalent to a Gaussian noise model with no loss function.
/// Null class is not robust so is a Gaussian ?
class GTSAM_EXPORT Null : public Base {
public:
typedef boost::shared_ptr<Null> shared_ptr;

Null(const ReweightScheme reweight = Block) : Base(reweight) {}
~Null() {}
double weight(double /*error*/) const { return 1.0; }
double loss(double error) const { return 0.5 * error * error; }
double residual(double error) const { return error; }
void print(const std::string &s) const;
bool equals(const Base & /*expected*/, double /*tol*/) const { return true; }
static shared_ptr Create();
Expand All @@ -158,7 +155,7 @@ class GTSAM_EXPORT Fair : public Base {

Fair(double c = 1.3998, const ReweightScheme reweight = Block);
double weight(double error) const override;
double loss(double error) const override;
double residual(double error) const override;
void print(const std::string &s) const override;
bool equals(const Base &expected, double tol = 1e-8) const override;
static shared_ptr Create(double c, const ReweightScheme reweight = Block);
Expand All @@ -183,7 +180,7 @@ class GTSAM_EXPORT Huber : public Base {

Huber(double k = 1.345, const ReweightScheme reweight = Block);
double weight(double error) const override;
double loss(double error) const override;
double residual(double error) const override;
void print(const std::string &s) const override;
bool equals(const Base &expected, double tol = 1e-8) const override;
static shared_ptr Create(double k, const ReweightScheme reweight = Block);
Expand Down Expand Up @@ -213,7 +210,7 @@ class GTSAM_EXPORT Cauchy : public Base {

Cauchy(double k = 0.1, const ReweightScheme reweight = Block);
double weight(double error) const override;
double loss(double error) const override;
double residual(double error) const override;
void print(const std::string &s) const override;
bool equals(const Base &expected, double tol = 1e-8) const override;
static shared_ptr Create(double k, const ReweightScheme reweight = Block);
Expand All @@ -238,7 +235,7 @@ class GTSAM_EXPORT Tukey : public Base {

Tukey(double c = 4.6851, const ReweightScheme reweight = Block);
double weight(double error) const override;
double loss(double error) const override;
double residual(double error) const override;
void print(const std::string &s) const override;
bool equals(const Base &expected, double tol = 1e-8) const override;
static shared_ptr Create(double k, const ReweightScheme reweight = Block);
Expand All @@ -263,7 +260,7 @@ class GTSAM_EXPORT Welsch : public Base {

Welsch(double c = 2.9846, const ReweightScheme reweight = Block);
double weight(double error) const override;
double loss(double error) const override;
double residual(double error) const override;
void print(const std::string &s) const override;
bool equals(const Base &expected, double tol = 1e-8) const override;
static shared_ptr Create(double k, const ReweightScheme reweight = Block);
Expand Down Expand Up @@ -299,7 +296,7 @@ class GTSAM_EXPORT GemanMcClure : public Base {
GemanMcClure(double c = 1.0, const ReweightScheme reweight = Block);
~GemanMcClure() {}
double weight(double error) const override;
double loss(double error) const override;
double residual(double error) const override;
void print(const std::string &s) const override;
bool equals(const Base &expected, double tol = 1e-8) const override;
static shared_ptr Create(double k, const ReweightScheme reweight = Block);
Expand Down Expand Up @@ -329,7 +326,7 @@ class GTSAM_EXPORT DCS : public Base {
DCS(double c = 1.0, const ReweightScheme reweight = Block);
~DCS() {}
double weight(double error) const override;
double loss(double error) const override;
double residual(double error) const override;
void print(const std::string &s) const override;
bool equals(const Base &expected, double tol = 1e-8) const override;
static shared_ptr Create(double k, const ReweightScheme reweight = Block);
Expand Down Expand Up @@ -362,7 +359,7 @@ class GTSAM_EXPORT L2WithDeadZone : public Base {

L2WithDeadZone(double k = 1.0, const ReweightScheme reweight = Block);
double weight(double error) const override;
double loss(double error) const override;
double residual(double error) const override;
void print(const std::string &s) const override;
bool equals(const Base &expected, double tol = 1e-8) const override;
static shared_ptr Create(double k, const ReweightScheme reweight = Block);
Expand Down
6 changes: 3 additions & 3 deletions gtsam/linear/NoiseModel.h
Original file line number Diff line number Diff line change
Expand Up @@ -703,11 +703,11 @@ namespace gtsam {
{ Vector b; Matrix B=A; this->WhitenSystem(B,b); return B; }
inline virtual Vector unwhiten(const Vector& /*v*/) const
{ throw std::invalid_argument("unwhiten is not currently supported for robust noise models."); }
// Fold the use of the m-estimator loss(...) function into distance(...)
// Fold the use of the m-estimator residual(...) function into distance(...)
inline virtual double distance(const Vector& v) const
{ return robust_->loss(this->unweightedWhiten(v).norm()); }
{ return robust_->residual(this->unweightedWhiten(v).norm()); }
inline virtual double distance_non_whitened(const Vector& v) const
{ return robust_->loss(v.norm()); }
{ return robust_->residual(v.norm()); }
// TODO: these are really robust iterated re-weighting support functions
virtual void WhitenSystem(Vector& b) const;
virtual void WhitenSystem(std::vector<Matrix>& A, Vector& b) const;
Expand Down
Loading

0 comments on commit 886b874

Please sign in to comment.