NonlinearFactor.h
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 
19 // \callgraph
20 
21 #pragma once
22 
23 #include <gtsam/nonlinear/Values.h>
26 #include <gtsam/inference/Factor.h>
28 
29 #include <boost/serialization/base_object.hpp>
30 #include <boost/assign/list_of.hpp>
31 
32 namespace gtsam {
33 
34 using boost::assign::cref_list_of;
35 
36 /* ************************************************************************* */
37 
43 class GTSAM_EXPORT NonlinearFactor: public Factor {
44 
45 protected:
46 
47  // Some handy typedefs
48  typedef Factor Base;
50 
51 public:
52 
53  typedef boost::shared_ptr<This> shared_ptr;
54 
57 
60 
64  template<typename CONTAINER>
65  NonlinearFactor(const CONTAINER& keys) :
66  Base(keys) {}
67 
71 
73  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
74  DefaultKeyFormatter) const override;
75 
77  virtual bool equals(const NonlinearFactor& f, double tol = 1e-9) const;
81 
83  virtual ~NonlinearFactor() {}
84 
85 
91  virtual double error(const Values& c) const = 0;
92 
94  virtual size_t dim() const = 0;
95 
106  virtual bool active(const Values& /*c*/) const { return true; }
107 
109  virtual boost::shared_ptr<GaussianFactor>
110  linearize(const Values& c) const = 0;
111 
118  virtual shared_ptr clone() const {
119  // TODO: choose better exception to throw here
120  throw std::runtime_error("NonlinearFactor::clone(): Attempting to clone factor with no clone() implemented!");
121  return shared_ptr();
122  }
123 
129  shared_ptr rekey(const std::map<Key,Key>& rekey_mapping) const;
130 
135  shared_ptr rekey(const KeyVector& new_keys) const;
136 
137 }; // \class NonlinearFactor
138 
140 template<> struct traits<NonlinearFactor> : public Testable<NonlinearFactor> {
141 };
142 
143 /* ************************************************************************* */
154 class GTSAM_EXPORT NoiseModelFactor: public NonlinearFactor {
155 
156 protected:
157 
158  // handy typedefs
159  typedef NonlinearFactor Base;
161 
164 public:
165 
166  typedef boost::shared_ptr<This> shared_ptr;
167 
170 
172  ~NoiseModelFactor() override {}
173 
177  template<typename CONTAINER>
178  NoiseModelFactor(const SharedNoiseModel& noiseModel, const CONTAINER& keys) :
179  Base(keys), noiseModel_(noiseModel) {}
180 
181 protected:
182 
186  NoiseModelFactor(const SharedNoiseModel& noiseModel) : noiseModel_(noiseModel) {}
187 
188 public:
189 
191  void print(const std::string& s = "",
192  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override;
193 
195  bool equals(const NonlinearFactor& f, double tol = 1e-9) const override;
196 
198  size_t dim() const override {
199  return noiseModel_->dim();
200  }
201 
203  const SharedNoiseModel& noiseModel() const {
204  return noiseModel_;
205  }
206 
213  virtual Vector unwhitenedError(const Values& x,
214  boost::optional<std::vector<Matrix>&> H = boost::none) const = 0;
215 
220  Vector whitenedError(const Values& c) const;
221 
225  Vector unweightedWhitenedError(const Values& c) const;
226 
230  double weight(const Values& c) const;
231 
238  double error(const Values& c) const override;
239 
245  boost::shared_ptr<GaussianFactor> linearize(const Values& x) const override;
246 
251  shared_ptr cloneWithNewNoiseModel(const SharedNoiseModel newNoise) const;
252 
253  private:
255  friend class boost::serialization::access;
256  template<class ARCHIVE>
257  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
258  ar & boost::serialization::make_nvp("NonlinearFactor",
259  boost::serialization::base_object<Base>(*this));
260  ar & BOOST_SERIALIZATION_NVP(noiseModel_);
261  }
262 
263 }; // \class NoiseModelFactor
264 
265 
266 /* ************************************************************************* */
267 
276 template<class VALUE>
278 
279 public:
280 
281  // typedefs for value types pulled from keys
282  typedef VALUE X;
283 
284 protected:
285 
288 
289 public:
292 
295 
296  ~NoiseModelFactor1() override {}
297 
298  inline Key key() const { return keys_[0]; }
299 
306  : Base(noiseModel, cref_list_of<1>(key1)) {}
307 
311 
317  const Values &x,
318  boost::optional<std::vector<Matrix> &> H = boost::none) const override {
319  if (this->active(x)) {
320  const X &x1 = x.at<X>(keys_[0]);
321  if (H) {
322  return evaluateError(x1, (*H)[0]);
323  } else {
324  return evaluateError(x1);
325  }
326  } else {
327  return Vector::Zero(this->dim());
328  }
329  }
330 
334 
340  virtual Vector
341  evaluateError(const X &x,
342  boost::optional<Matrix &> H = boost::none) const = 0;
343 
345 
346 private:
348  friend class boost::serialization::access;
349  template<class ARCHIVE>
350  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
351  ar & boost::serialization::make_nvp("NoiseModelFactor",
352  boost::serialization::base_object<Base>(*this));
353  }
354 };// \class NoiseModelFactor1
355 
356 
357 /* ************************************************************************* */
360 template<class VALUE1, class VALUE2>
362 
363 public:
364 
365  // typedefs for value types pulled from keys
366  typedef VALUE1 X1;
367  typedef VALUE2 X2;
368 
369 protected:
370 
373 
374 public:
375 
380 
387  NoiseModelFactor2(const SharedNoiseModel& noiseModel, Key j1, Key j2) :
388  Base(noiseModel, cref_list_of<2>(j1)(j2)) {}
389 
390  ~NoiseModelFactor2() override {}
391 
393  inline Key key1() const { return keys_[0]; }
394  inline Key key2() const { return keys_[1]; }
395 
398  Vector unwhitenedError(const Values& x, boost::optional<std::vector<Matrix>&> H = boost::none) const override {
399  if(this->active(x)) {
400  const X1& x1 = x.at<X1>(keys_[0]);
401  const X2& x2 = x.at<X2>(keys_[1]);
402  if(H) {
403  return evaluateError(x1, x2, (*H)[0], (*H)[1]);
404  } else {
405  return evaluateError(x1, x2);
406  }
407  } else {
408  return Vector::Zero(this->dim());
409  }
410  }
411 
417  virtual Vector
418  evaluateError(const X1&, const X2&, boost::optional<Matrix&> H1 =
419  boost::none, boost::optional<Matrix&> H2 = boost::none) const = 0;
420 
421 private:
422 
424  friend class boost::serialization::access;
425  template<class ARCHIVE>
426  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
427  ar & boost::serialization::make_nvp("NoiseModelFactor",
428  boost::serialization::base_object<Base>(*this));
429  }
430 }; // \class NoiseModelFactor2
431 
432 /* ************************************************************************* */
435 template<class VALUE1, class VALUE2, class VALUE3>
437 
438 public:
439 
440  // typedefs for value types pulled from keys
441  typedef VALUE1 X1;
442  typedef VALUE2 X2;
443  typedef VALUE3 X3;
444 
445 protected:
446 
449 
450 public:
451 
456 
464  NoiseModelFactor3(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3) :
465  Base(noiseModel, cref_list_of<3>(j1)(j2)(j3)) {}
466 
467  ~NoiseModelFactor3() override {}
468 
470  inline Key key1() const { return keys_[0]; }
471  inline Key key2() const { return keys_[1]; }
472  inline Key key3() const { return keys_[2]; }
473 
476  Vector unwhitenedError(const Values& x, boost::optional<std::vector<Matrix>&> H = boost::none) const override {
477  if(this->active(x)) {
478  if(H)
479  return evaluateError(x.at<X1>(keys_[0]), x.at<X2>(keys_[1]), x.at<X3>(keys_[2]), (*H)[0], (*H)[1], (*H)[2]);
480  else
481  return evaluateError(x.at<X1>(keys_[0]), x.at<X2>(keys_[1]), x.at<X3>(keys_[2]));
482  } else {
483  return Vector::Zero(this->dim());
484  }
485  }
486 
492  virtual Vector
493  evaluateError(const X1&, const X2&, const X3&,
494  boost::optional<Matrix&> H1 = boost::none,
495  boost::optional<Matrix&> H2 = boost::none,
496  boost::optional<Matrix&> H3 = boost::none) const = 0;
497 
498 private:
499 
501  friend class boost::serialization::access;
502  template<class ARCHIVE>
503  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
504  ar & boost::serialization::make_nvp("NoiseModelFactor",
505  boost::serialization::base_object<Base>(*this));
506  }
507 }; // \class NoiseModelFactor3
508 
509 /* ************************************************************************* */
512 template<class VALUE1, class VALUE2, class VALUE3, class VALUE4>
514 
515 public:
516 
517  // typedefs for value types pulled from keys
518  typedef VALUE1 X1;
519  typedef VALUE2 X2;
520  typedef VALUE3 X3;
521  typedef VALUE4 X4;
522 
523 protected:
524 
527 
528 public:
529 
534 
543  NoiseModelFactor4(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3, Key j4) :
544  Base(noiseModel, cref_list_of<4>(j1)(j2)(j3)(j4)) {}
545 
546  ~NoiseModelFactor4() override {}
547 
549  inline Key key1() const { return keys_[0]; }
550  inline Key key2() const { return keys_[1]; }
551  inline Key key3() const { return keys_[2]; }
552  inline Key key4() const { return keys_[3]; }
553 
556  Vector unwhitenedError(const Values& x, boost::optional<std::vector<Matrix>&> H = boost::none) const override {
557  if(this->active(x)) {
558  if(H)
559  return evaluateError(x.at<X1>(keys_[0]), x.at<X2>(keys_[1]), x.at<X3>(keys_[2]), x.at<X4>(keys_[3]), (*H)[0], (*H)[1], (*H)[2], (*H)[3]);
560  else
561  return evaluateError(x.at<X1>(keys_[0]), x.at<X2>(keys_[1]), x.at<X3>(keys_[2]), x.at<X4>(keys_[3]));
562  } else {
563  return Vector::Zero(this->dim());
564  }
565  }
566 
572  virtual Vector
573  evaluateError(const X1&, const X2&, const X3&, const X4&,
574  boost::optional<Matrix&> H1 = boost::none,
575  boost::optional<Matrix&> H2 = boost::none,
576  boost::optional<Matrix&> H3 = boost::none,
577  boost::optional<Matrix&> H4 = boost::none) const = 0;
578 
579 private:
580 
582  friend class boost::serialization::access;
583  template<class ARCHIVE>
584  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
585  ar & boost::serialization::make_nvp("NoiseModelFactor",
586  boost::serialization::base_object<Base>(*this));
587  }
588 }; // \class NoiseModelFactor4
589 
590 /* ************************************************************************* */
593 template<class VALUE1, class VALUE2, class VALUE3, class VALUE4, class VALUE5>
595 
596 public:
597 
598  // typedefs for value types pulled from keys
599  typedef VALUE1 X1;
600  typedef VALUE2 X2;
601  typedef VALUE3 X3;
602  typedef VALUE4 X4;
603  typedef VALUE5 X5;
604 
605 protected:
606 
609 
610 public:
611 
616 
626  NoiseModelFactor5(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3, Key j4, Key j5) :
627  Base(noiseModel, cref_list_of<5>(j1)(j2)(j3)(j4)(j5)) {}
628 
629  ~NoiseModelFactor5() override {}
630 
632  inline Key key1() const { return keys_[0]; }
633  inline Key key2() const { return keys_[1]; }
634  inline Key key3() const { return keys_[2]; }
635  inline Key key4() const { return keys_[3]; }
636  inline Key key5() const { return keys_[4]; }
637 
640  Vector unwhitenedError(const Values& x, boost::optional<std::vector<Matrix>&> H = boost::none) const override {
641  if(this->active(x)) {
642  if(H)
643  return evaluateError(x.at<X1>(keys_[0]), x.at<X2>(keys_[1]), x.at<X3>(keys_[2]), x.at<X4>(keys_[3]), x.at<X5>(keys_[4]), (*H)[0], (*H)[1], (*H)[2], (*H)[3], (*H)[4]);
644  else
645  return evaluateError(x.at<X1>(keys_[0]), x.at<X2>(keys_[1]), x.at<X3>(keys_[2]), x.at<X4>(keys_[3]), x.at<X5>(keys_[4]));
646  } else {
647  return Vector::Zero(this->dim());
648  }
649  }
650 
656  virtual Vector
657  evaluateError(const X1&, const X2&, const X3&, const X4&, const X5&,
658  boost::optional<Matrix&> H1 = boost::none,
659  boost::optional<Matrix&> H2 = boost::none,
660  boost::optional<Matrix&> H3 = boost::none,
661  boost::optional<Matrix&> H4 = boost::none,
662  boost::optional<Matrix&> H5 = boost::none) const = 0;
663 
664 private:
665 
667  friend class boost::serialization::access;
668  template<class ARCHIVE>
669  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
670  ar & boost::serialization::make_nvp("NoiseModelFactor",
671  boost::serialization::base_object<Base>(*this));
672  }
673 }; // \class NoiseModelFactor5
674 
675 /* ************************************************************************* */
678 template<class VALUE1, class VALUE2, class VALUE3, class VALUE4, class VALUE5, class VALUE6>
680 
681 public:
682 
683  // typedefs for value types pulled from keys
684  typedef VALUE1 X1;
685  typedef VALUE2 X2;
686  typedef VALUE3 X3;
687  typedef VALUE4 X4;
688  typedef VALUE5 X5;
689  typedef VALUE6 X6;
690 
691 protected:
692 
695 
696 public:
697 
702 
713  NoiseModelFactor6(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3, Key j4, Key j5, Key j6) :
714  Base(noiseModel, cref_list_of<6>(j1)(j2)(j3)(j4)(j5)(j6)) {}
715 
716  ~NoiseModelFactor6() override {}
717 
719  inline Key key1() const { return keys_[0]; }
720  inline Key key2() const { return keys_[1]; }
721  inline Key key3() const { return keys_[2]; }
722  inline Key key4() const { return keys_[3]; }
723  inline Key key5() const { return keys_[4]; }
724  inline Key key6() const { return keys_[5]; }
725 
728  Vector unwhitenedError(const Values& x, boost::optional<std::vector<Matrix>&> H = boost::none) const override {
729  if(this->active(x)) {
730  if(H)
731  return evaluateError(x.at<X1>(keys_[0]), x.at<X2>(keys_[1]), x.at<X3>(keys_[2]), x.at<X4>(keys_[3]), x.at<X5>(keys_[4]), x.at<X6>(keys_[5]), (*H)[0], (*H)[1], (*H)[2], (*H)[3], (*H)[4], (*H)[5]);
732  else
733  return evaluateError(x.at<X1>(keys_[0]), x.at<X2>(keys_[1]), x.at<X3>(keys_[2]), x.at<X4>(keys_[3]), x.at<X5>(keys_[4]), x.at<X6>(keys_[5]));
734  } else {
735  return Vector::Zero(this->dim());
736  }
737  }
738 
744  virtual Vector
745  evaluateError(const X1&, const X2&, const X3&, const X4&, const X5&, const X6&,
746  boost::optional<Matrix&> H1 = boost::none,
747  boost::optional<Matrix&> H2 = boost::none,
748  boost::optional<Matrix&> H3 = boost::none,
749  boost::optional<Matrix&> H4 = boost::none,
750  boost::optional<Matrix&> H5 = boost::none,
751  boost::optional<Matrix&> H6 = boost::none) const = 0;
752 
753 private:
754 
756  friend class boost::serialization::access;
757  template<class ARCHIVE>
758  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
759  ar & boost::serialization::make_nvp("NoiseModelFactor",
760  boost::serialization::base_object<Base>(*this));
761  }
762 }; // \class NoiseModelFactor6
763 
764 /* ************************************************************************* */
765 
766 } // \namespace gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
void serialize(ARCHIVE &ar, const unsigned int)
Vector unwhitenedError(const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override
Vector unwhitenedError(const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override
NoiseModelFactor1(const SharedNoiseModel &noiseModel, Key key1)
size_t dim() const override
NoiseModelFactor5(const SharedNoiseModel &noiseModel, Key j1, Key j2, Key j3, Key j4, Key j5)
A non-templated config holding any types of Manifold-group elements.
NoiseModelFactor4< VALUE1, VALUE2, VALUE3, VALUE4 > This
void serialize(ARCHIVE &ar, const unsigned int)
void serialize(ARCHIVE &ar, const unsigned int)
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
NoiseModelFactor5< VALUE1, VALUE2, VALUE3, VALUE4, VALUE5 > This
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
NoiseModelFactor3(const SharedNoiseModel &noiseModel, Key j1, Key j2, Key j3)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
NoiseModelFactor6(const SharedNoiseModel &noiseModel, Key j1, Key j2, Key j3, Key j4, Key j5, Key j6)
NoiseModelFactor2< VALUE1, VALUE2 > This
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
NoiseModelFactor1< VALUE > This
const SharedNoiseModel & noiseModel() const
access to the noise model
void serialize(ARCHIVE &ar, const unsigned int)
virtual bool active(const Values &) const
NoiseModelFactor6< VALUE1, VALUE2, VALUE3, VALUE4, VALUE5, VALUE6 > This
const Symbol key1('v', 1)
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
Vector unwhitenedError(const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override
Eigen::VectorXd Vector
Definition: Vector.h:38
const ValueType at(Key j) const
Definition: Values-inl.h:342
NoiseModelFactor(const SharedNoiseModel &noiseModel, const CONTAINER &keys)
NoiseModelFactor3< VALUE1, VALUE2, VALUE3 > This
boost::shared_ptr< This > shared_ptr
NonlinearFactor This
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
boost::shared_ptr< This > shared_ptr
Vector unwhitenedError(const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override
const mpreal dim(const mpreal &a, const mpreal &b, mp_rnd_t r=mpreal::get_default_rnd())
Definition: mpreal.h:2201
traits
Definition: chartTesting.h:28
void serialize(ARCHIVE &ar, const unsigned int)
NoiseModelFactor2(const SharedNoiseModel &noiseModel, Key j1, Key j2)
SharedNoiseModel noiseModel_
Pose3 x1
Definition: testPose3.cpp:588
static double error
Definition: testRot3.cpp:39
Special class for optional Jacobian arguments.
const G double tol
Definition: Group.h:83
const KeyVector keys
Vector unwhitenedError(const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override
virtual shared_ptr clone() const
NoiseModelFactor4(const SharedNoiseModel &noiseModel, Key j1, Key j2, Key j3, Key j4)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
NoiseModelFactor(const SharedNoiseModel &noiseModel)
NonlinearFactor(const CONTAINER &keys)
void serialize(ARCHIVE &ar, const unsigned int)
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
Vector unwhitenedError(const Values &x, boost::optional< std::vector< Matrix > & > H=boost::none) const override
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
void serialize(ARCHIVE &ar, const unsigned int)
The base class for all factors.


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:43:03