24 #include <gtsam/dllexport.h> 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> 36 namespace noiseModel {
57 namespace mEstimator {
70 typedef std::shared_ptr<Base> shared_ptr;
96 virtual double loss(
double distance)
const {
return 0; }
108 virtual double weight(
double distance)
const = 0;
110 virtual void print(
const std::string &s)
const = 0;
111 virtual bool equals(
const Base &expected,
double tol = 1e-8)
const = 0;
113 double sqrtWeight(
double distance)
const {
return std::sqrt(weight(distance)); }
117 Vector weight(
const Vector &error)
const;
120 Vector sqrtWeight(
const Vector &error)
const;
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;
131 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 133 friend class boost::serialization::access;
134 template <
class ARCHIVE>
135 void serialize(ARCHIVE &ar,
const unsigned int ) {
136 ar &BOOST_SERIALIZATION_NVP(reweight_);
152 typedef std::shared_ptr<Null> shared_ptr;
156 double weight(
double )
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 & ,
double )
const override {
return true; }
160 static shared_ptr Create();
163 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 165 friend class boost::serialization::access;
166 template <
class ARCHIVE>
167 void serialize(ARCHIVE &ar,
const unsigned int ) {
168 ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
186 typedef std::shared_ptr<Fair> shared_ptr;
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_; }
197 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 199 friend class boost::serialization::access;
200 template <
class ARCHIVE>
201 void serialize(ARCHIVE &ar,
const unsigned int ) {
202 ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
203 ar &BOOST_SERIALIZATION_NVP(c_);
221 typedef std::shared_ptr<Huber> shared_ptr;
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_; }
232 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 234 friend class boost::serialization::access;
235 template <
class ARCHIVE>
236 void serialize(ARCHIVE &ar,
const unsigned int ) {
237 ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
238 ar &BOOST_SERIALIZATION_NVP(k_);
258 double k_, ksquared_;
261 typedef std::shared_ptr<Cauchy> shared_ptr;
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_; }
272 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 274 friend class boost::serialization::access;
275 template <
class ARCHIVE>
276 void serialize(ARCHIVE &ar,
const unsigned int ) {
277 ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
278 ar &BOOST_SERIALIZATION_NVP(k_);
279 ar &BOOST_SERIALIZATION_NVP(ksquared_);
294 double c_, csquared_;
297 typedef std::shared_ptr<Tukey> shared_ptr;
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_; }
308 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 310 friend class boost::serialization::access;
311 template <
class ARCHIVE>
312 void serialize(ARCHIVE &ar,
const unsigned int ) {
313 ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
314 ar &BOOST_SERIALIZATION_NVP(c_);
329 double c_, csquared_;
332 typedef std::shared_ptr<Welsch> shared_ptr;
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_; }
343 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 345 friend class boost::serialization::access;
346 template <
class ARCHIVE>
347 void serialize(ARCHIVE &ar,
const unsigned int ) {
348 ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
349 ar &BOOST_SERIALIZATION_NVP(c_);
350 ar &BOOST_SERIALIZATION_NVP(csquared_);
367 typedef std::shared_ptr<GemanMcClure> shared_ptr;
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_; }
382 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 384 friend class boost::serialization::access;
385 template <
class ARCHIVE>
386 void serialize(ARCHIVE &ar,
const unsigned int ) {
387 ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
388 ar &BOOST_SERIALIZATION_NVP(c_);
407 typedef std::shared_ptr<DCS> shared_ptr;
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_; }
422 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 424 friend class boost::serialization::access;
425 template <
class ARCHIVE>
426 void serialize(ARCHIVE &ar,
const unsigned int ) {
427 ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
428 ar &BOOST_SERIALIZATION_NVP(c_);
451 typedef std::shared_ptr<L2WithDeadZone> shared_ptr;
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_; }
462 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 464 friend class boost::serialization::access;
465 template <
class ARCHIVE>
466 void serialize(ARCHIVE &ar,
const unsigned int ) {
467 ar &BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
468 ar &BOOST_SERIALIZATION_NVP(k_);
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::string serialize(const T &input)
serializes to a string
Definition: serialization.h:113
ReweightScheme
Definition: LossFunctions.h:69
Definition: LossFunctions.h:292
Definition: LossFunctions.h:216
Definition: LossFunctions.h:181
Definition: LossFunctions.h:150
Definition: Testable.h:112
ReweightScheme reweight_
Strategy for reweighting.
Definition: LossFunctions.h:74
Definition: LossFunctions.h:365
GTSAM_EXPORT void print(const Matrix &A, const std::string &s, std::ostream &stream)
Definition: LossFunctions.h:65
typedef and functions to augment Eigen's MatrixXd
Definition: LossFunctions.h:256
Definition: LossFunctions.h:405
Definition: chartTesting.h:28
double weight(double) const override
Definition: LossFunctions.h:156
virtual double loss(double distance) const
Definition: LossFunctions.h:96
Definition: LossFunctions.h:446
double loss(double distance) const override
Definition: LossFunctions.h:157
Definition: LossFunctions.h:327