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 #include <boost/serialization/extended_type_info.hpp>
27 #include <boost/serialization/nvp.hpp>
28 #include <boost/serialization/version.hpp>
29 #include <boost/serialization/optional.hpp>
30 #include <boost/serialization/shared_ptr.hpp>
31 #include <boost/serialization/singleton.hpp>
32 
33 namespace gtsam {
34 namespace noiseModel {
35 // clang-format off
54 // clang-format on
55 namespace mEstimator {
56 
57 //---------------------------------------------------------------------------------------
58 
59 class GTSAM_EXPORT Base {
60  public:
61  enum ReweightScheme { Scalar, Block };
62  typedef boost::shared_ptr<Base> shared_ptr;
63 
64  protected:
68 
69  public:
70  Base(const ReweightScheme reweight = Block) : reweight_(reweight) {}
71  virtual ~Base() {}
72 
73  /*
74  * This method is responsible for returning the total penalty for a given
75  * amount of error. For example, this method is responsible for implementing
76  * the quadratic function for an L2 penalty, the absolute value function for
77  * an L1 penalty, etc.
78  *
79  * TODO(mikebosse): When the loss function has as input the norm of the
80  * error vector, then it prevents implementations of asymmeric loss
81  * functions. It would be better for this function to accept the vector and
82  * internally call the norm if necessary.
83  */
84  virtual double loss(double distance) const { return 0; };
85 
86  /*
87  * This method is responsible for returning the weight function for a given
88  * amount of error. The weight function is related to the analytic derivative
89  * of the loss function. See
90  * https://members.loria.fr/MOBerger/Enseignement/Master2/Documents/ZhangIVC-97-01.pdf
91  * for details. This method is required when optimizing cost functions with
92  * robust penalties using iteratively re-weighted least squares.
93  */
94  virtual double weight(double distance) const = 0;
95 
96  virtual void print(const std::string &s) const = 0;
97  virtual bool equals(const Base &expected, double tol = 1e-8) const = 0;
98 
99  double sqrtWeight(double distance) const { return std::sqrt(weight(distance)); }
100 
103  Vector weight(const Vector &error) const;
104 
106  Vector sqrtWeight(const Vector &error) const {
107  return weight(error).cwiseSqrt();
108  }
109 
112  void reweight(Vector &error) const;
113  void reweight(std::vector<Matrix> &A, Vector &error) const;
114  void reweight(Matrix &A, Vector &error) const;
115  void reweight(Matrix &A1, Matrix &A2, Vector &error) const;
116  void reweight(Matrix &A1, Matrix &A2, Matrix &A3, Vector &error) const;
117 
118  private:
120  friend class boost::serialization::access;
121  template <class ARCHIVE>
122  void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
123  ar &BOOST_SERIALIZATION_NVP(reweight_);
124  }
125 };
126 
128 class GTSAM_EXPORT Null : public Base {
129  public:
130  typedef boost::shared_ptr<Null> shared_ptr;
131 
132  Null(const ReweightScheme reweight = Block) : Base(reweight) {}
133  ~Null() override {}
134  double weight(double /*error*/) const override { return 1.0; }
135  double loss(double distance) const override { return 0.5 * distance * distance; }
136  void print(const std::string &s) const override;
137  bool equals(const Base & /*expected*/, double /*tol*/) const override { return true; }
138  static shared_ptr Create();
139 
140  private:
142  friend class boost::serialization::access;
143  template <class ARCHIVE>
144  void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
145  ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
146  }
147 };
148 
150 class GTSAM_EXPORT Fair : public Base {
151  protected:
152  double c_;
153 
154  public:
155  typedef boost::shared_ptr<Fair> shared_ptr;
156 
157  Fair(double c = 1.3998, const ReweightScheme reweight = Block);
158  double weight(double distance) const override;
159  double loss(double distance) const override;
160  void print(const std::string &s) const override;
161  bool equals(const Base &expected, double tol = 1e-8) const override;
162  static shared_ptr Create(double c, const ReweightScheme reweight = Block);
163 
164  private:
166  friend class boost::serialization::access;
167  template <class ARCHIVE>
168  void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
169  ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
170  ar &BOOST_SERIALIZATION_NVP(c_);
171  }
172 };
173 
175 class GTSAM_EXPORT Huber : public Base {
176  protected:
177  double k_;
178 
179  public:
180  typedef boost::shared_ptr<Huber> shared_ptr;
181 
182  Huber(double k = 1.345, const ReweightScheme reweight = Block);
183  double weight(double distance) const override;
184  double loss(double distance) const override;
185  void print(const std::string &s) const override;
186  bool equals(const Base &expected, double tol = 1e-8) const override;
187  static shared_ptr Create(double k, const ReweightScheme reweight = Block);
188 
189  private:
191  friend class boost::serialization::access;
192  template <class ARCHIVE>
193  void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
194  ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
195  ar &BOOST_SERIALIZATION_NVP(k_);
196  }
197 };
198 
205 class GTSAM_EXPORT Cauchy : public Base {
206  protected:
207  double k_, ksquared_;
208 
209  public:
210  typedef boost::shared_ptr<Cauchy> shared_ptr;
211 
212  Cauchy(double k = 0.1, const ReweightScheme reweight = Block);
213  double weight(double distance) const override;
214  double loss(double distance) const override;
215  void print(const std::string &s) const override;
216  bool equals(const Base &expected, double tol = 1e-8) const override;
217  static shared_ptr Create(double k, const ReweightScheme reweight = Block);
218 
219  private:
221  friend class boost::serialization::access;
222  template <class ARCHIVE>
223  void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
224  ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
225  ar &BOOST_SERIALIZATION_NVP(k_);
226  }
227 };
228 
230 class GTSAM_EXPORT Tukey : public Base {
231  protected:
232  double c_, csquared_;
233 
234  public:
235  typedef boost::shared_ptr<Tukey> shared_ptr;
236 
237  Tukey(double c = 4.6851, const ReweightScheme reweight = Block);
238  double weight(double distance) const override;
239  double loss(double distance) const override;
240  void print(const std::string &s) const override;
241  bool equals(const Base &expected, double tol = 1e-8) const override;
242  static shared_ptr Create(double k, const ReweightScheme reweight = Block);
243 
244  private:
246  friend class boost::serialization::access;
247  template <class ARCHIVE>
248  void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
249  ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
250  ar &BOOST_SERIALIZATION_NVP(c_);
251  }
252 };
253 
255 class GTSAM_EXPORT Welsch : public Base {
256  protected:
257  double c_, csquared_;
258 
259  public:
260  typedef boost::shared_ptr<Welsch> shared_ptr;
261 
262  Welsch(double c = 2.9846, const ReweightScheme reweight = Block);
263  double weight(double distance) const override;
264  double loss(double distance) const override;
265  void print(const std::string &s) const override;
266  bool equals(const Base &expected, double tol = 1e-8) const override;
267  static shared_ptr Create(double k, const ReweightScheme reweight = Block);
268 
269  private:
271  friend class boost::serialization::access;
272  template <class ARCHIVE>
273  void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
274  ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
275  ar &BOOST_SERIALIZATION_NVP(c_);
276  }
277 };
278 
285 class GTSAM_EXPORT GemanMcClure : public Base {
286  public:
287  typedef boost::shared_ptr<GemanMcClure> shared_ptr;
288 
289  GemanMcClure(double c = 1.0, const ReweightScheme reweight = Block);
290  ~GemanMcClure() override {}
291  double weight(double distance) const override;
292  double loss(double distance) const override;
293  void print(const std::string &s) const override;
294  bool equals(const Base &expected, double tol = 1e-8) const override;
295  static shared_ptr Create(double k, const ReweightScheme reweight = Block);
296 
297  protected:
298  double c_;
299 
300  private:
302  friend class boost::serialization::access;
303  template <class ARCHIVE>
304  void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
305  ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
306  ar &BOOST_SERIALIZATION_NVP(c_);
307  }
308 };
309 
315 class GTSAM_EXPORT DCS : public Base {
316  public:
317  typedef boost::shared_ptr<DCS> shared_ptr;
318 
319  DCS(double c = 1.0, const ReweightScheme reweight = Block);
320  ~DCS() override {}
321  double weight(double distance) const override;
322  double loss(double distance) const override;
323  void print(const std::string &s) const override;
324  bool equals(const Base &expected, double tol = 1e-8) const override;
325  static shared_ptr Create(double k, const ReweightScheme reweight = Block);
326 
327  protected:
328  double c_;
329 
330  private:
332  friend class boost::serialization::access;
333  template <class ARCHIVE>
334  void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
335  ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
336  ar &BOOST_SERIALIZATION_NVP(c_);
337  }
338 };
339 
346 class GTSAM_EXPORT L2WithDeadZone : public Base {
347  protected:
348  double k_;
349 
350  public:
351  typedef boost::shared_ptr<L2WithDeadZone> shared_ptr;
352 
353  L2WithDeadZone(double k = 1.0, const ReweightScheme reweight = Block);
354  double weight(double distance) const override;
355  double loss(double distance) const override;
356  void print(const std::string &s) const override;
357  bool equals(const Base &expected, double tol = 1e-8) const override;
358  static shared_ptr Create(double k, const ReweightScheme reweight = Block);
359 
360  private:
362  friend class boost::serialization::access;
363  template <class ARCHIVE>
364  void serialize(ARCHIVE &ar, const unsigned int /*version*/) {
365  ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
366  ar &BOOST_SERIALIZATION_NVP(k_);
367  }
368 };
369 
370 } // namespace mEstimator
371 } // namespace noiseModel
372 } // namespace gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
boost::shared_ptr< Huber > shared_ptr
void serialize(ARCHIVE &ar, const unsigned int)
void serialize(ARCHIVE &ar, const unsigned int)
void serialize(ARCHIVE &ar, const unsigned int)
void serialize(ARCHIVE &ar, const unsigned int)
Concept check for values that can be used in unit tests.
Matrix expected
Definition: testMatrix.cpp:974
void serialize(ARCHIVE &ar, const unsigned int)
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Tukey implements the "Tukey" robust error model (Zhang97ivc)
Huber implements the "Huber" robust error model (Zhang97ivc)
void serialize(ARCHIVE &ar, const unsigned int)
bool equals(const Base &, double) const override
boost::shared_ptr< L2WithDeadZone > shared_ptr
Fair implements the "Fair" robust error model (Zhang97ivc)
Null class should behave as Gaussian.
Vector sqrtWeight(const Vector &error) const
Base(const ReweightScheme reweight=Block)
Definition: LossFunctions.h:70
Eigen::VectorXd Vector
Definition: Vector.h:38
boost::shared_ptr< Null > shared_ptr
boost::shared_ptr< GemanMcClure > shared_ptr
void serialize(ARCHIVE &ar, const unsigned int)
virtual double loss(double distance) const
Definition: LossFunctions.h:84
double sqrtWeight(double distance) const
Definition: LossFunctions.h:99
void serialize(ARCHIVE &ar, const unsigned int)
boost::shared_ptr< Tukey > shared_ptr
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
boost::shared_ptr< Base > shared_ptr
Definition: LossFunctions.h:62
boost::shared_ptr< Cauchy > shared_ptr
traits
Definition: chartTesting.h:28
double weight(double) const override
boost::shared_ptr< DCS > shared_ptr
static double error
Definition: testRot3.cpp:39
double loss(double distance) const override
const G double tol
Definition: Group.h:83
void serialize(ARCHIVE &ar, const unsigned int)
boost::shared_ptr< Fair > shared_ptr
boost::shared_ptr< Welsch > shared_ptr
Welsch implements the "Welsch" robust error model (Zhang97ivc)
Null(const ReweightScheme reweight=Block)
void serialize(ARCHIVE &ar, const unsigned int)


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