LossFunctions.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
20 
21 #include <iostream>
22 
23 using namespace std;
24 
25 namespace gtsam {
26 namespace noiseModel {
27 
28 /* ************************************************************************* */
29 // M-Estimator
30 /* ************************************************************************* */
31 
32 namespace mEstimator {
33 
34 Vector Base::weight(const Vector& error) const {
35  const size_t n = error.rows();
36  Vector w(n);
37  for (size_t i = 0; i < n; ++i)
38  w(i) = weight(error(i));
39  return w;
40 }
41 
42 // The following three functions re-weight block matrices and a vector
43 // according to their weight implementation
44 
45 void Base::reweight(Vector& error) const {
46  if (reweight_ == Block) {
47  const double w = sqrtWeight(error.norm());
48  error *= w;
49  } else {
50  error.array() *= weight(error).cwiseSqrt().array();
51  }
52 }
53 
54 // Reweight n block matrices with one error vector
55 void Base::reweight(vector<Matrix> &A, Vector &error) const {
56  if ( reweight_ == Block ) {
57  const double w = sqrtWeight(error.norm());
58  for(Matrix& Aj: A) {
59  Aj *= w;
60  }
61  error *= w;
62  }
63  else {
64  const Vector W = sqrtWeight(error);
65  for(Matrix& Aj: A) {
67  }
68  error = W.cwiseProduct(error);
69  }
70 }
71 
72 // Reweight one block matrix with one error vector
73 void Base::reweight(Matrix &A, Vector &error) const {
74  if ( reweight_ == Block ) {
75  const double w = sqrtWeight(error.norm());
76  A *= w;
77  error *= w;
78  }
79  else {
80  const Vector W = sqrtWeight(error);
82  error = W.cwiseProduct(error);
83  }
84 }
85 
86 // Reweight two block matrix with one error vector
87 void Base::reweight(Matrix &A1, Matrix &A2, Vector &error) const {
88  if ( reweight_ == Block ) {
89  const double w = sqrtWeight(error.norm());
90  A1 *= w;
91  A2 *= w;
92  error *= w;
93  }
94  else {
95  const Vector W = sqrtWeight(error);
98  error = W.cwiseProduct(error);
99  }
100 }
101 
102 // Reweight three block matrix with one error vector
103 void Base::reweight(Matrix &A1, Matrix &A2, Matrix &A3, Vector &error) const {
104  if ( reweight_ == Block ) {
105  const double w = sqrtWeight(error.norm());
106  A1 *= w;
107  A2 *= w;
108  A3 *= w;
109  error *= w;
110  }
111  else {
112  const Vector W = sqrtWeight(error);
113  vector_scale_inplace(W,A1);
114  vector_scale_inplace(W,A2);
115  vector_scale_inplace(W,A3);
116  error = W.cwiseProduct(error);
117  }
118 }
119 
120 /* ************************************************************************* */
121 // Null model
122 /* ************************************************************************* */
123 
124 void Null::print(const std::string &s="") const
125 { cout << s << "null ()" << endl; }
126 
127 Null::shared_ptr Null::Create()
128 { return shared_ptr(new Null()); }
129 
130 /* ************************************************************************* */
131 // Fair
132 /* ************************************************************************* */
133 
134 Fair::Fair(double c, const ReweightScheme reweight) : Base(reweight), c_(c) {
135  if (c_ <= 0) {
136  throw runtime_error("mEstimator Fair takes only positive double in constructor.");
137  }
138 }
139 
140 double Fair::weight(double distance) const {
141  return 1.0 / (1.0 + std::abs(distance) / c_);
142 }
143 
144 double Fair::loss(double distance) const {
145  const double absError = std::abs(distance);
146  const double normalizedError = absError / c_;
147  const double c_2 = c_ * c_;
148  return c_2 * (normalizedError - std::log1p(normalizedError));
149 }
150 
151 void Fair::print(const std::string &s="") const
152 { cout << s << "fair (" << c_ << ")" << endl; }
153 
154 bool Fair::equals(const Base &expected, double tol) const {
155  const Fair* p = dynamic_cast<const Fair*> (&expected);
156  if (p == nullptr) return false;
157  return std::abs(c_ - p->c_ ) < tol;
158 }
159 
161 { return shared_ptr(new Fair(c, reweight)); }
162 
163 /* ************************************************************************* */
164 // Huber
165 /* ************************************************************************* */
166 
167 Huber::Huber(double k, const ReweightScheme reweight) : Base(reweight), k_(k) {
168  if (k_ <= 0) {
169  throw runtime_error("mEstimator Huber takes only positive double in constructor.");
170  }
171 }
172 
173 double Huber::weight(double distance) const {
174  const double absError = std::abs(distance);
175  return (absError <= k_) ? (1.0) : (k_ / absError);
176 }
177 
178 double Huber::loss(double distance) const {
179  const double absError = std::abs(distance);
180  if (absError <= k_) { // |x| <= k
181  return distance*distance / 2;
182  } else { // |x| > k
183  return k_ * (absError - (k_/2));
184  }
185 }
186 
187 void Huber::print(const std::string &s="") const {
188  cout << s << "huber (" << k_ << ")" << endl;
189 }
190 
191 bool Huber::equals(const Base &expected, double tol) const {
192  const Huber* p = dynamic_cast<const Huber*>(&expected);
193  if (p == nullptr) return false;
194  return std::abs(k_ - p->k_) < tol;
195 }
196 
198  return shared_ptr(new Huber(c, reweight));
199 }
200 
201 /* ************************************************************************* */
202 // Cauchy
203 /* ************************************************************************* */
204 
205 Cauchy::Cauchy(double k, const ReweightScheme reweight) : Base(reweight), k_(k), ksquared_(k * k) {
206  if (k <= 0) {
207  throw runtime_error("mEstimator Cauchy takes only positive double in constructor.");
208  }
209 }
210 
211 double Cauchy::weight(double distance) const {
212  return ksquared_ / (ksquared_ + distance*distance);
213 }
214 
215 double Cauchy::loss(double distance) const {
216  const double val = std::log1p(distance * distance / ksquared_);
217  return ksquared_ * val * 0.5;
218 }
219 
220 void Cauchy::print(const std::string &s="") const {
221  cout << s << "cauchy (" << k_ << ")" << endl;
222 }
223 
224 bool Cauchy::equals(const Base &expected, double tol) const {
225  const Cauchy* p = dynamic_cast<const Cauchy*>(&expected);
226  if (p == nullptr) return false;
227  return std::abs(ksquared_ - p->ksquared_) < tol;
228 }
229 
231  return shared_ptr(new Cauchy(c, reweight));
232 }
233 
234 /* ************************************************************************* */
235 // Tukey
236 /* ************************************************************************* */
237 
238 Tukey::Tukey(double c, const ReweightScheme reweight) : Base(reweight), c_(c), csquared_(c * c) {
239  if (c <= 0) {
240  throw runtime_error("mEstimator Tukey takes only positive double in constructor.");
241  }
242 }
243 
244 double Tukey::weight(double distance) const {
245  if (std::abs(distance) <= c_) {
246  const double one_minus_xc2 = 1.0 - distance*distance/csquared_;
247  return one_minus_xc2 * one_minus_xc2;
248  }
249  return 0.0;
250 }
251 
252 double Tukey::loss(double distance) const {
253  double absError = std::abs(distance);
254  if (absError <= c_) {
255  const double one_minus_xc2 = 1.0 - distance*distance/csquared_;
256  const double t = one_minus_xc2*one_minus_xc2*one_minus_xc2;
257  return csquared_ * (1 - t) / 6.0;
258  } else {
259  return csquared_ / 6.0;
260  }
261 }
262 
263 void Tukey::print(const std::string &s="") const {
264  std::cout << s << ": Tukey (" << c_ << ")" << std::endl;
265 }
266 
267 bool Tukey::equals(const Base &expected, double tol) const {
268  const Tukey* p = dynamic_cast<const Tukey*>(&expected);
269  if (p == nullptr) return false;
270  return std::abs(c_ - p->c_) < tol;
271 }
272 
274  return shared_ptr(new Tukey(c, reweight));
275 }
276 
277 /* ************************************************************************* */
278 // Welsch
279 /* ************************************************************************* */
280 
281 Welsch::Welsch(double c, const ReweightScheme reweight) : Base(reweight), c_(c), csquared_(c * c) {}
282 
283 double Welsch::weight(double distance) const {
284  const double xc2 = (distance*distance)/csquared_;
285  return std::exp(-xc2);
286 }
287 
288 double Welsch::loss(double distance) const {
289  const double xc2 = (distance*distance)/csquared_;
290  return csquared_ * 0.5 * -std::expm1(-xc2);
291 }
292 
293 void Welsch::print(const std::string &s="") const {
294  std::cout << s << ": Welsch (" << c_ << ")" << std::endl;
295 }
296 
297 bool Welsch::equals(const Base &expected, double tol) const {
298  const Welsch* p = dynamic_cast<const Welsch*>(&expected);
299  if (p == nullptr) return false;
300  return std::abs(c_ - p->c_) < tol;
301 }
302 
304  return shared_ptr(new Welsch(c, reweight));
305 }
306 
307 /* ************************************************************************* */
308 // GemanMcClure
309 /* ************************************************************************* */
311  : Base(reweight), c_(c) {
312 }
313 
314 double GemanMcClure::weight(double distance) const {
315  const double c2 = c_*c_;
316  const double c4 = c2*c2;
317  const double c2error = c2 + distance*distance;
318  return c4/(c2error*c2error);
319 }
320 
321 double GemanMcClure::loss(double distance) const {
322  const double c2 = c_*c_;
323  const double error2 = distance*distance;
324  return 0.5 * (c2 * error2) / (c2 + error2);
325 }
326 
327 void GemanMcClure::print(const std::string &s="") const {
328  std::cout << s << ": Geman-McClure (" << c_ << ")" << std::endl;
329 }
330 
331 bool GemanMcClure::equals(const Base &expected, double tol) const {
332  const GemanMcClure* p = dynamic_cast<const GemanMcClure*>(&expected);
333  if (p == nullptr) return false;
334  return std::abs(c_ - p->c_) < tol;
335 }
336 
338  return shared_ptr(new GemanMcClure(c, reweight));
339 }
340 
341 /* ************************************************************************* */
342 // DCS
343 /* ************************************************************************* */
345  : Base(reweight), c_(c) {
346 }
347 
348 double DCS::weight(double distance) const {
349  const double e2 = distance*distance;
350  if (e2 > c_)
351  {
352  const double w = 2.0*c_/(c_ + e2);
353  return w*w;
354  }
355 
356  return 1.0;
357 }
358 
359 double DCS::loss(double distance) const {
360  // This is the simplified version of Eq 9 from (Agarwal13icra)
361  // after you simplify and cancel terms.
362  const double e2 = distance*distance;
363  const double e4 = e2*e2;
364  const double c2 = c_*c_;
365 
366  return (c2*e2 + c_*e4) / ((e2 + c_)*(e2 + c_));
367 }
368 
369 void DCS::print(const std::string &s="") const {
370  std::cout << s << ": DCS (" << c_ << ")" << std::endl;
371 }
372 
373 bool DCS::equals(const Base &expected, double tol) const {
374  const DCS* p = dynamic_cast<const DCS*>(&expected);
375  if (p == nullptr) return false;
376  return std::abs(c_ - p->c_) < tol;
377 }
378 
380  return shared_ptr(new DCS(c, reweight));
381 }
382 
383 /* ************************************************************************* */
384 // L2WithDeadZone
385 /* ************************************************************************* */
386 
388  : Base(reweight), k_(k) {
389  if (k_ <= 0) {
390  throw runtime_error("mEstimator L2WithDeadZone takes only positive double in constructor.");
391  }
392 }
393 
394 double L2WithDeadZone::weight(double distance) const {
395  // note that this code is slightly uglier than residual, because there are three distinct
396  // cases to handle (left of deadzone, deadzone, right of deadzone) instead of the two
397  // cases (deadzone, non-deadzone) in residual.
398  if (std::abs(distance) <= k_) return 0.0;
399  else if (distance > k_) return (-k_+distance)/distance;
400  else return (k_+distance)/distance;
401 }
402 
403 double L2WithDeadZone::loss(double distance) const {
404  const double abs_error = std::abs(distance);
405  return (abs_error < k_) ? 0.0 : 0.5*(k_-abs_error)*(k_-abs_error);
406 }
407 
408 void L2WithDeadZone::print(const std::string &s="") const {
409  std::cout << s << ": L2WithDeadZone (" << k_ << ")" << std::endl;
410 }
411 
412 bool L2WithDeadZone::equals(const Base &expected, double tol) const {
413  const L2WithDeadZone* p = dynamic_cast<const L2WithDeadZone*>(&expected);
414  if (p == nullptr) return false;
415  return std::abs(k_ - p->k_) < tol;
416 }
417 
419  return shared_ptr(new L2WithDeadZone(k, reweight));
420 }
421 
422 } // namespace mEstimator
423 } // namespace noiseModel
424 } // gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
boost::shared_ptr< Huber > shared_ptr
static shared_ptr Create(double k, const ReweightScheme reweight=Block)
static shared_ptr Create(double k, const ReweightScheme reweight=Block)
DCS(double c=1.0, const ReweightScheme reweight=Block)
static const Key c2
Tukey(double c=4.6851, const ReweightScheme reweight=Block)
double loss(double distance) const override
EIGEN_DEVICE_FUNC const ExpReturnType exp() const
Matrix expected
Definition: testMatrix.cpp:974
bool equals(const Base &expected, double tol=1e-8) const override
void vector_scale_inplace(const Vector &v, Matrix &A, bool inf_mask)
Definition: Matrix.cpp:481
void reweight(Vector &error) const
int n
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
bool equals(const Base &expected, double tol=1e-8) const override
Tukey implements the "Tukey" robust error model (Zhang97ivc)
double weight(double distance) const override
const mpreal expm1(const mpreal &x, mp_rnd_t r=mpreal::get_default_rnd())
Definition: mpreal.h:2260
double weight(double distance) const override
L2WithDeadZone(double k=1.0, const ReweightScheme reweight=Block)
Definition: Half.h:150
Key W(std::uint64_t j)
Huber implements the "Huber" robust error model (Zhang97ivc)
double loss(double distance) const override
double loss(double distance) const override
void print(const std::string &s) const override
bool equals(const Base &expected, double tol=1e-8) const override
boost::shared_ptr< L2WithDeadZone > shared_ptr
Fair implements the "Fair" robust error model (Zhang97ivc)
Welsch(double c=2.9846, const ReweightScheme reweight=Block)
Null class should behave as Gaussian.
double loss(double distance) const override
bool equals(const Base &expected, double tol=1e-8) const override
void print(const std::string &s) const override
bool equals(const Base &expected, double tol=1e-8) const override
double loss(double distance) const override
Eigen::VectorXd Vector
Definition: Vector.h:38
boost::shared_ptr< Null > shared_ptr
EIGEN_DEVICE_FUNC const Log1pReturnType log1p() const
boost::shared_ptr< GemanMcClure > shared_ptr
double loss(double distance) const override
double weight(double distance) const override
static shared_ptr Create(double k, const ReweightScheme reweight=Block)
Fair(double c=1.3998, const ReweightScheme reweight=Block)
Cauchy(double k=0.1, const ReweightScheme reweight=Block)
boost::shared_ptr< Tukey > shared_ptr
double weight(double distance) const override
RealScalar s
boost::shared_ptr< Base > shared_ptr
Definition: LossFunctions.h:62
double weight(double distance) const override
boost::shared_ptr< Cauchy > shared_ptr
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)
void print(const std::string &s) const override
RowVector3d w
double weight(double distance) const override
traits
Definition: chartTesting.h:28
void print(const std::string &s) const override
double loss(double distance) const override
static shared_ptr Create(double c, const ReweightScheme reweight=Block)
double weight(double distance) const override
boost::shared_ptr< DCS > shared_ptr
static shared_ptr Create(double k, const ReweightScheme reweight=Block)
void print(const std::string &s) const override
static shared_ptr Create(double k, const ReweightScheme reweight=Block)
float * p
void print(const std::string &s) const override
static double error
Definition: testRot3.cpp:39
Huber(double k=1.345, const ReweightScheme reweight=Block)
bool equals(const Base &expected, double tol=1e-8) const override
const G double tol
Definition: Group.h:83
boost::shared_ptr< Fair > shared_ptr
boost::shared_ptr< Welsch > shared_ptr
#define abs(x)
Definition: datatypes.h:17
bool equals(const Base &expected, double tol=1e-8) const override
GemanMcClure(double c=1.0, const ReweightScheme reweight=Block)
double loss(double distance) const override
void print(const std::string &s) const override
static shared_ptr Create(double k, const ReweightScheme reweight=Block)
Welsch implements the "Welsch" robust error model (Zhang97ivc)
Point2 t(10, 10)
double weight(double distance) const override


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:34