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


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:34:34