LossFunctions.h
Go to the documentation of this file.
1 
2 /* ----------------------------------------------------------------------------
3 
4  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
5  * Atlanta, Georgia 30332-0415
6  * All Rights Reserved
7  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
8 
9  * See LICENSE for the license information
10 
11  * -------------------------------------------------------------------------- */
12 
20 #pragma once
21 
22 #include <gtsam/base/Matrix.h>
23 #include <gtsam/base/Testable.h>
24 #include <gtsam/dllexport.h>
25 
26 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
27 #include <boost/serialization/extended_type_info.hpp>
28 #include <boost/serialization/nvp.hpp>
29 #include <boost/serialization/version.hpp>
30 #include <boost/serialization/optional.hpp>
31 #include <boost/serialization/shared_ptr.hpp>
32 #include <boost/serialization/singleton.hpp>
33 #endif
34 
35 namespace gtsam {
36 namespace noiseModel {
37 // clang-format off
56 // clang-format on
57 namespace mEstimator {
58 
65 class GTSAM_EXPORT Base {
66  public:
69  enum ReweightScheme { Scalar, Block };
70  typedef std::shared_ptr<Base> shared_ptr;
71 
72  protected:
75 
76  public:
77  Base(const ReweightScheme reweight = Block) : reweight_(reweight) {}
78  virtual ~Base() {}
79 
81  ReweightScheme reweightScheme() const { return reweight_; }
82 
96  virtual double loss(double distance) const { return 0; }
97 
108  virtual double weight(double distance) const = 0;
109 
110  virtual void print(const std::string &s) const = 0;
111  virtual bool equals(const Base &expected, double tol = 1e-8) const = 0;
112 
113  double sqrtWeight(double distance) const { return std::sqrt(weight(distance)); }
114 
117  Vector weight(const Vector &error) const;
118 
120  Vector sqrtWeight(const Vector &error) const;
121 
124  void reweight(Vector &error) const;
125  void reweight(std::vector<Matrix> &A, Vector &error) const;
126  void reweight(Matrix &A, Vector &error) const;
127  void reweight(Matrix &A1, Matrix &A2, Vector &error) const;
128  void reweight(Matrix &A1, Matrix &A2, Matrix &A3, Vector &error) const;
129 
130  private:
131 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
132 
133  friend class boost::serialization::access;
134  template <class ARCHIVE>
135  void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
136  ar &BOOST_SERIALIZATION_NVP(reweight_);
137  }
138 #endif
139 };
140 
150 class GTSAM_EXPORT Null : public Base {
151  public:
152  typedef std::shared_ptr<Null> shared_ptr;
153 
154  Null(const ReweightScheme reweight = Block) : Base(reweight) {}
155  ~Null() override {}
156  double weight(double /*error*/) const override { return 1.0; }
157  double loss(double distance) const override { return 0.5 * distance * distance; }
158  void print(const std::string &s) const override;
159  bool equals(const Base & /*expected*/, double /*tol*/) const override { return true; }
160  static shared_ptr Create();
161 
162  private:
163 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
164 
165  friend class boost::serialization::access;
166  template <class ARCHIVE>
167  void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
168  ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
169  }
170 #endif
171 };
172 
181 class GTSAM_EXPORT Fair : public Base {
182  protected:
183  double c_;
184 
185  public:
186  typedef std::shared_ptr<Fair> shared_ptr;
187 
188  Fair(double c = 1.3998, const ReweightScheme reweight = Block);
189  double weight(double distance) const override;
190  double loss(double distance) const override;
191  void print(const std::string &s) const override;
192  bool equals(const Base &expected, double tol = 1e-8) const override;
193  static shared_ptr Create(double c, const ReweightScheme reweight = Block);
194  double modelParameter() const { return c_; }
195 
196  private:
197 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
198 
199  friend class boost::serialization::access;
200  template <class ARCHIVE>
201  void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
202  ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
203  ar &BOOST_SERIALIZATION_NVP(c_);
204  }
205 #endif
206 };
207 
216 class GTSAM_EXPORT Huber : public Base {
217  protected:
218  double k_;
219 
220  public:
221  typedef std::shared_ptr<Huber> shared_ptr;
222 
223  Huber(double k = 1.345, const ReweightScheme reweight = Block);
224  double weight(double distance) const override;
225  double loss(double distance) const override;
226  void print(const std::string &s) const override;
227  bool equals(const Base &expected, double tol = 1e-8) const override;
228  static shared_ptr Create(double k, const ReweightScheme reweight = Block);
229  double modelParameter() const { return k_; }
230 
231  private:
232 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
233 
234  friend class boost::serialization::access;
235  template <class ARCHIVE>
236  void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
237  ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
238  ar &BOOST_SERIALIZATION_NVP(k_);
239  }
240 #endif
241 };
242 
256 class GTSAM_EXPORT Cauchy : public Base {
257  protected:
258  double k_, ksquared_;
259 
260  public:
261  typedef std::shared_ptr<Cauchy> shared_ptr;
262 
263  Cauchy(double k = 0.1, const ReweightScheme reweight = Block);
264  double weight(double distance) const override;
265  double loss(double distance) const override;
266  void print(const std::string &s) const override;
267  bool equals(const Base &expected, double tol = 1e-8) const override;
268  static shared_ptr Create(double k, const ReweightScheme reweight = Block);
269  double modelParameter() const { return k_; }
270 
271  private:
272 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
273 
274  friend class boost::serialization::access;
275  template <class ARCHIVE>
276  void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
277  ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
278  ar &BOOST_SERIALIZATION_NVP(k_);
279  ar &BOOST_SERIALIZATION_NVP(ksquared_);
280  }
281 #endif
282 };
283 
292 class GTSAM_EXPORT Tukey : public Base {
293  protected:
294  double c_, csquared_;
295 
296  public:
297  typedef std::shared_ptr<Tukey> shared_ptr;
298 
299  Tukey(double c = 4.6851, const ReweightScheme reweight = Block);
300  double weight(double distance) const override;
301  double loss(double distance) const override;
302  void print(const std::string &s) const override;
303  bool equals(const Base &expected, double tol = 1e-8) const override;
304  static shared_ptr Create(double k, const ReweightScheme reweight = Block);
305  double modelParameter() const { return c_; }
306 
307  private:
308 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
309 
310  friend class boost::serialization::access;
311  template <class ARCHIVE>
312  void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
313  ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
314  ar &BOOST_SERIALIZATION_NVP(c_);
315  }
316 #endif
317 };
318 
327 class GTSAM_EXPORT Welsch : public Base {
328  protected:
329  double c_, csquared_;
330 
331  public:
332  typedef std::shared_ptr<Welsch> shared_ptr;
333 
334  Welsch(double c = 2.9846, const ReweightScheme reweight = Block);
335  double weight(double distance) const override;
336  double loss(double distance) const override;
337  void print(const std::string &s) const override;
338  bool equals(const Base &expected, double tol = 1e-8) const override;
339  static shared_ptr Create(double k, const ReweightScheme reweight = Block);
340  double modelParameter() const { return c_; }
341 
342  private:
343 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
344 
345  friend class boost::serialization::access;
346  template <class ARCHIVE>
347  void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
348  ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
349  ar &BOOST_SERIALIZATION_NVP(c_);
350  ar &BOOST_SERIALIZATION_NVP(csquared_);
351  }
352 #endif
353 };
354 
365 class GTSAM_EXPORT GemanMcClure : public Base {
366  public:
367  typedef std::shared_ptr<GemanMcClure> shared_ptr;
368 
369  GemanMcClure(double c = 1.0, const ReweightScheme reweight = Block);
370  ~GemanMcClure() override {}
371  double weight(double distance) const override;
372  double loss(double distance) const override;
373  void print(const std::string &s) const override;
374  bool equals(const Base &expected, double tol = 1e-8) const override;
375  static shared_ptr Create(double k, const ReweightScheme reweight = Block);
376  double modelParameter() const { return c_; }
377 
378  protected:
379  double c_;
380 
381  private:
382 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
383 
384  friend class boost::serialization::access;
385  template <class ARCHIVE>
386  void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
387  ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
388  ar &BOOST_SERIALIZATION_NVP(c_);
389  }
390 #endif
391 };
392 
405 class GTSAM_EXPORT DCS : public Base {
406  public:
407  typedef std::shared_ptr<DCS> shared_ptr;
408 
409  DCS(double c = 1.0, const ReweightScheme reweight = Block);
410  ~DCS() override {}
411  double weight(double distance) const override;
412  double loss(double distance) const override;
413  void print(const std::string &s) const override;
414  bool equals(const Base &expected, double tol = 1e-8) const override;
415  static shared_ptr Create(double k, const ReweightScheme reweight = Block);
416  double modelParameter() const { return c_; }
417 
418  protected:
419  double c_;
420 
421  private:
422 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
423 
424  friend class boost::serialization::access;
425  template <class ARCHIVE>
426  void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
427  ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
428  ar &BOOST_SERIALIZATION_NVP(c_);
429  }
430 #endif
431 };
432 
446 class GTSAM_EXPORT L2WithDeadZone : public Base {
447  protected:
448  double k_;
449 
450  public:
451  typedef std::shared_ptr<L2WithDeadZone> shared_ptr;
452 
453  L2WithDeadZone(double k = 1.0, const ReweightScheme reweight = Block);
454  double weight(double distance) const override;
455  double loss(double distance) const override;
456  void print(const std::string &s) const override;
457  bool equals(const Base &expected, double tol = 1e-8) const override;
458  static shared_ptr Create(double k, const ReweightScheme reweight = Block);
459  double modelParameter() const { return k_; }
460 
461  private:
462 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
463 
464  friend class boost::serialization::access;
465  template <class ARCHIVE>
466  void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
467  ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
468  ar &BOOST_SERIALIZATION_NVP(k_);
469  }
470 #endif
471 };
472 
473 } // namespace mEstimator
474 } // namespace noiseModel
475 } // namespace gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
static Matrix A1
std::shared_ptr< L2WithDeadZone > shared_ptr
std::shared_ptr< DCS > shared_ptr
ReweightScheme reweightScheme() const
Returns the reweight scheme, as explained in ReweightScheme.
Definition: LossFunctions.h:81
Concept check for values that can be used in unit tests.
std::shared_ptr< Tukey > shared_ptr
std::string serialize(const T &input)
serializes to a string
Matrix expected
Definition: testMatrix.cpp:971
std::shared_ptr< Null > shared_ptr
std::shared_ptr< Base > shared_ptr
Definition: LossFunctions.h:70
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
Double_ distance(const OrientedPlane3_ &p)
bool equals(const Base &, double) const override
ReweightScheme reweight_
Strategy for reweighting.
Definition: LossFunctions.h:74
Base(const ReweightScheme reweight=Block)
Definition: LossFunctions.h:77
Eigen::VectorXd Vector
Definition: Vector.h:38
double sqrtWeight(double distance) const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
std::shared_ptr< Welsch > shared_ptr
traits
Definition: chartTesting.h:28
std::shared_ptr< Fair > shared_ptr
double weight(double) const override
std::shared_ptr< GemanMcClure > shared_ptr
virtual double loss(double distance) const
Definition: LossFunctions.h:96
std::shared_ptr< Huber > shared_ptr
static double error
Definition: testRot3.cpp:37
double loss(double distance) const override
Jet< T, N > sqrt(const Jet< T, N > &f)
Definition: jet.h:418
const G double tol
Definition: Group.h:86
std::shared_ptr< Cauchy > shared_ptr
Null(const ReweightScheme reweight=Block)


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