GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
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 
20 // \callgraph
21 
22 #pragma once
23 
24 #include <gtsam/nonlinear/Values.h>
27 #include <gtsam/inference/Factor.h>
29 #include <gtsam/base/utilities.h>
30 
31 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
32 #include <boost/serialization/base_object.hpp>
33 #endif
34 #include <cstddef>
35 #include <type_traits>
36 
37 namespace gtsam {
38 
39 /* ************************************************************************* */
40 
49 #define OptionalNone static_cast<Matrix*>(nullptr)
50 
55 using OptionalMatrixType = Matrix*;
56 
61 using OptionalMatrixVecType = std::vector<Matrix>*;
62 
68 class GTSAM_EXPORT NonlinearFactor: public Factor {
69 
70 protected:
71 
72  // Some handy typedefs
73  typedef Factor Base;
74  typedef NonlinearFactor This;
75 
76 public:
77 
78  typedef std::shared_ptr<This> shared_ptr;
79 
82 
85 
89  template<typename CONTAINER>
90  NonlinearFactor(const CONTAINER& keys) :
91  Base(keys) {}
92 
96 
98  void print(const std::string& s = "", const KeyFormatter& keyFormatter =
99  DefaultKeyFormatter) const override;
100 
102  virtual bool equals(const NonlinearFactor& f, double tol = 1e-9) const;
103 
107 
120  virtual double error(const Values& c) const;
121 
126  double error(const HybridValues& c) const override;
127 
129  virtual size_t dim() const = 0;
130 
141  virtual bool active(const Values& /*c*/) const { return true; }
142 
144  virtual std::shared_ptr<GaussianFactor>
145  linearize(const Values& c) const = 0;
146 
153  virtual shared_ptr clone() const {
154  // TODO: choose better exception to throw here
155  throw std::runtime_error("NonlinearFactor::clone(): Attempting to clone factor with no clone() implemented!");
156  return shared_ptr();
157  }
158 
164  virtual shared_ptr rekey(const std::map<Key,Key>& rekey_mapping) const;
165 
170  virtual shared_ptr rekey(const KeyVector& new_keys) const;
171 
176  virtual bool sendable() const {
177  return true;
178  }
179 
180 }; // \class NonlinearFactor
181 
183 template<> struct traits<NonlinearFactor> : public Testable<NonlinearFactor> {
184 };
185 
186 /* ************************************************************************* */
197 class GTSAM_EXPORT NoiseModelFactor: public NonlinearFactor {
198 
199 protected:
200 
201  // handy typedefs
202  typedef NonlinearFactor Base;
203  typedef NoiseModelFactor This;
204 
205  SharedNoiseModel noiseModel_;
207 public:
208 
209  typedef std::shared_ptr<This> shared_ptr;
210 
213 
215  ~NoiseModelFactor() override {}
216 
220  template<typename CONTAINER>
221  NoiseModelFactor(const SharedNoiseModel& noiseModel, const CONTAINER& keys) :
222  Base(keys), noiseModel_(noiseModel) {}
223 
224 protected:
225 
229  NoiseModelFactor(const SharedNoiseModel& noiseModel) : noiseModel_(noiseModel) {}
230 
231 public:
233  void print(const std::string& s = "",
234  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override;
235 
237  bool equals(const NonlinearFactor& f, double tol = 1e-9) const override;
238 
240  size_t dim() const override {
241  return noiseModel_->dim();
242  }
243 
245  const SharedNoiseModel& noiseModel() const {
246  return noiseModel_;
247  }
248 
255  virtual Vector unwhitenedError(const Values& x, OptionalMatrixVecType H = nullptr) const = 0;
256 
263  Vector unwhitenedError(const Values& x, std::vector<Matrix>& H) const {
264  return unwhitenedError(x, &H);
265  }
266 
271  Vector whitenedError(const Values& c) const;
272 
276  Vector unweightedWhitenedError(const Values& c) const;
277 
281  double weight(const Values& c) const;
282 
289  double error(const Values& c) const override;
290 
296  std::shared_ptr<GaussianFactor> linearize(const Values& x) const override;
297 
302  shared_ptr cloneWithNewNoiseModel(const SharedNoiseModel newNoise) const;
303 
304  private:
305 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
306 
307  friend class boost::serialization::access;
308  template<class ARCHIVE>
309  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
310  ar & boost::serialization::make_nvp("NonlinearFactor",
311  boost::serialization::base_object<Base>(*this));
312  ar & BOOST_SERIALIZATION_NVP(noiseModel_);
313  }
314 #endif
315 
316 }; // \class NoiseModelFactor
317 
318 /* ************************************************************************* */
319 namespace detail {
332 template <typename, typename...>
334 template <typename T1>
336  using X = T1;
337  using X1 = T1;
338 };
339 template <typename T1, typename T2>
341  using X1 = T1;
342  using X2 = T2;
343 };
344 template <typename T1, typename T2, typename T3>
346  using X1 = T1;
347  using X2 = T2;
348  using X3 = T3;
349 };
350 template <typename T1, typename T2, typename T3, typename T4>
352  using X1 = T1;
353  using X2 = T2;
354  using X3 = T3;
355  using X4 = T4;
356 };
357 template <typename T1, typename T2, typename T3, typename T4, typename T5>
359  using X1 = T1;
360  using X2 = T2;
361  using X3 = T3;
362  using X4 = T4;
363  using X5 = T5;
364 };
365 template <typename T1, typename T2, typename T3, typename T4, typename T5,
366  typename T6, typename... TExtra>
367 struct NoiseModelFactorAliases<T1, T2, T3, T4, T5, T6, TExtra...> {
368  using X1 = T1;
369  using X2 = T2;
370  using X3 = T3;
371  using X4 = T4;
372  using X5 = T5;
373  using X6 = T6;
374 };
375 } // namespace detail
376 
377 /* ************************************************************************* */
430 template <class... ValueTypes>
432  : public NoiseModelFactor,
433  public detail::NoiseModelFactorAliases<ValueTypes...> {
434  public:
436  enum { N = sizeof...(ValueTypes) };
437 
439 
440 protected:
441  using Base = NoiseModelFactor;
442  using This = NoiseModelFactorN<ValueTypes...>;
443 
446 
447  template <typename From, typename To>
448  using IsConvertible =
449  typename std::enable_if<std::is_convertible<From, To>::value, void>::type;
450 
451  template <int I>
452  using IndexIsValid = typename std::enable_if<(I >= 1) && (I <= N),
453  void>::type; // 1-indexed!
454 
455  template <typename Container>
456  using ContainerElementType =
457  typename std::decay<decltype(*std::declval<Container>().begin())>::type;
458  template <typename Container>
459  using IsContainerOfKeys = IsConvertible<ContainerElementType<Container>, Key>;
460 
465  template <typename Ret, typename ...Args>
466  using AreAllMatrixRefs = std::enable_if_t<(... &&
467  std::is_convertible<Args, Matrix&>::value), Ret>;
468 
469  template<typename Arg>
470  using IsMatrixPointer = std::is_same<typename std::decay_t<Arg>, Matrix*>;
471 
472  template<typename Arg>
473  using IsNullpointer = std::is_same<typename std::decay_t<Arg>, std::nullptr_t>;
474 
479  template <typename Ret, typename ...Args>
480  using AreAllMatrixPtrs = std::enable_if_t<(... &&
481  (IsMatrixPointer<Args>::value || IsNullpointer<Args>::value)), Ret>;
482 
484 
485  /* Like std::void_t, except produces `OptionalMatrixType` instead of
486  * `void`. Used to expand fixed-type parameter-packs with same length as
487  * ValueTypes. */
488  template <typename T = void>
489  using OptionalMatrixTypeT = Matrix*;
490 
491  /* Like std::void_t, except produces `Key` instead of `void`. Used to expand
492  * fixed-type parameter-packs with same length as ValueTypes. */
493  template <typename T>
494  using KeyType = Key;
495 
496  /* Like std::void_t, except produces `Matrix` instead of
497  * `void`. Used to expand fixed-type parameter-packs with same length as
498  * ValueTypes. This helps in creating an evaluateError overload that accepts
499  * Matrices instead of pointers to matrices */
500  template <typename T = void>
501  using MatrixTypeT = Matrix;
502 
503  public:
523  template <int I, typename = IndexIsValid<I>>
524  using ValueType =
525  typename std::tuple_element<I - 1, std::tuple<ValueTypes...>>::type;
526 
527  public:
528 
531 
534 
543  KeyType<ValueTypes>... keys)
544  : Base(noiseModel, std::array<Key, N>{keys...}) {}
545 
553  template <typename CONTAINER = std::initializer_list<Key>,
554  typename = IsContainerOfKeys<CONTAINER>>
555  NoiseModelFactorN(const SharedNoiseModel& noiseModel, CONTAINER keys)
556  : Base(noiseModel, keys) {
557  if (keys.size() != N) {
558  throw std::invalid_argument(
559  "NoiseModelFactorN: wrong number of keys given");
560  }
561  }
562 
564 
565  ~NoiseModelFactorN() override {}
566 
581  template <int I = 1>
582  inline Key key() const {
583  static_assert(I <= N, "Index out of bounds");
584  return keys_[I - 1];
585  }
586 
589 
607  const Values& x,
608  OptionalMatrixVecType H = nullptr) const override {
609  return unwhitenedError(gtsam::index_sequence_for<ValueTypes...>{}, x,
610  H);
611  }
612 
616 
639  virtual Vector evaluateError(const ValueTypes&... x,
640  OptionalMatrixTypeT<ValueTypes>... H) const = 0;
641 
649  Vector evaluateError(const ValueTypes&... x, MatrixTypeT<ValueTypes>&... H) const {
650  return evaluateError(x..., (&H)...);
651  }
652 
656 
663  inline Vector evaluateError(const ValueTypes&... x) const {
664  return evaluateError(x..., OptionalMatrixTypeT<ValueTypes>()...);
665  }
666 
671  template <typename... OptionalJacArgs, typename = IndexIsValid<sizeof...(OptionalJacArgs) + 1>>
673  OptionalJacArgs&&... H) const {
674  return evaluateError(x..., (&H)...);
675  }
676 
681  template <typename... OptionalJacArgs, typename = IndexIsValid<sizeof...(OptionalJacArgs) + 1>>
683  OptionalJacArgs&&... H) const {
684  // If they are pointer version, ensure to cast them all to be Matrix* types
685  // This will ensure any arguments inferred as std::nonetype_t are cast to (Matrix*) nullptr
686  // This guides the compiler to the correct overload which is the one that takes pointers
687  return evaluateError(x...,
688  std::forward<OptionalJacArgs>(H)..., static_cast<OptionalMatrixType>(OptionalNone));
689  }
690 
692 
693  private:
700  template <std::size_t... Indices>
701  inline Vector unwhitenedError(
703  const Values& x,
704  OptionalMatrixVecType H = nullptr) const {
705  if (this->active(x)) {
706  if (H) {
707  return evaluateError(x.at<ValueTypes>(keys_[Indices])...,
708  (*H)[Indices]...);
709  } else {
710  return evaluateError(x.at<ValueTypes>(keys_[Indices])...);
711  }
712  } else {
713  return Vector::Zero(this->dim());
714  }
715  }
716 
717 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
718 
719  friend class boost::serialization::access;
720  template <class ARCHIVE>
721  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
722  ar& boost::serialization::make_nvp(
723  "NoiseModelFactor", boost::serialization::base_object<Base>(*this));
724  }
725 #endif
726 
727  public:
730 
731  inline Key key1() const {
732  return key<1>();
733  }
734  template <int I = 2>
735  inline Key key2() const {
736  static_assert(I <= N, "Index out of bounds");
737  return key<2>();
738  }
739  template <int I = 3>
740  inline Key key3() const {
741  static_assert(I <= N, "Index out of bounds");
742  return key<3>();
743  }
744  template <int I = 4>
745  inline Key key4() const {
746  static_assert(I <= N, "Index out of bounds");
747  return key<4>();
748  }
749  template <int I = 5>
750  inline Key key5() const {
751  static_assert(I <= N, "Index out of bounds");
752  return key<5>();
753  }
754  template <int I = 6>
755  inline Key key6() const {
756  static_assert(I <= N, "Index out of bounds");
757  return key<6>();
758  }
759 
761 
762 }; // \class NoiseModelFactorN
763 
764 #define NoiseModelFactor1 NoiseModelFactorN
765 #define NoiseModelFactor2 NoiseModelFactorN
766 #define NoiseModelFactor3 NoiseModelFactorN
767 #define NoiseModelFactor4 NoiseModelFactorN
768 #define NoiseModelFactor5 NoiseModelFactorN
769 #define NoiseModelFactor6 NoiseModelFactorN
770 
771 } // namespace gtsam
Definition: HybridValues.h:38
typename std::enable_if< B, T >::type enable_if_t
An shorthand alias for accessing the ::type inside std::enable_if that can be used in a template dire...
Definition: make_shared.h:30
Definition: NonlinearFactor.h:431
NoiseModelFactorN(const SharedNoiseModel &noiseModel, KeyType< ValueTypes >... keys)
Definition: NonlinearFactor.h:542
std::vector< Matrix > * OptionalMatrixVecType
Definition: NonlinearFactor.h:61
size_t dim() const override
Definition: NonlinearFactor.h:240
AreAllMatrixRefs< Vector, OptionalJacArgs... > evaluateError(const ValueTypes &... x, OptionalJacArgs &&... H) const
Definition: NonlinearFactor.h:672
A non-templated config holding any types of Manifold-group elements.
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:113
Definition: NonlinearFactor.h:340
const ValueType at(Key j) const
Definition: Values-inl.h:204
Definition: Factor.h:69
Definition: Testable.h:152
Definition: Group.h:43
Key key() const
Definition: NonlinearFactor.h:582
Definition: NonlinearFactor.h:68
Vector unwhitenedError(const Values &x, std::vector< Matrix > &H) const
Definition: NonlinearFactor.h:263
NoiseModelFactor()
Definition: NonlinearFactor.h:212
NonlinearFactor()
Definition: NonlinearFactor.h:84
~NoiseModelFactor() override
Definition: NonlinearFactor.h:215
Definition: NonlinearFactor.h:197
#define OptionalNone
Definition: NonlinearFactor.h:49
Vector evaluateError(const ValueTypes &... x) const
Definition: NonlinearFactor.h:663
Definition: Testable.h:112
const SharedNoiseModel & noiseModel() const
access to the noise model
Definition: NonlinearFactor.h:245
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:55
AreAllMatrixPtrs< Vector, OptionalJacArgs... > evaluateError(const ValueTypes &... x, OptionalJacArgs &&... H) const
Definition: NonlinearFactor.h:682
NoiseModelFactor(const SharedNoiseModel &noiseModel, const CONTAINER &keys)
Definition: NonlinearFactor.h:221
GTSAM_EXPORT void print(const Matrix &A, const std::string &s, std::ostream &stream)
NoiseModelFactorN(const SharedNoiseModel &noiseModel, CONTAINER keys)
Definition: NonlinearFactor.h:555
std::enable_if_t<(... &&(IsMatrixPointer< Args >::value||IsNullpointer< Args >::value)), Ret > AreAllMatrixPtrs
Definition: NonlinearFactor.h:481
Definition: utilities.h:35
Definition: Values.h:65
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
Vector evaluateError(const ValueTypes &... x, MatrixTypeT< ValueTypes > &... H) const
Definition: NonlinearFactor.h:649
Definition: chartTesting.h:28
Vector unwhitenedError(const Values &x, OptionalMatrixVecType H=nullptr) const override
Definition: NonlinearFactor.h:606
std::shared_ptr< This > shared_ptr
Definition: NonlinearFactor.h:209
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
virtual Vector unwhitenedError(const Values &x, OptionalMatrixVecType H=nullptr) const =0
NoiseModelFactorN()
Default Constructor for I/O.
Definition: NonlinearFactor.h:533
virtual bool active(const Values &) const
Definition: NonlinearFactor.h:141
Definition: NonlinearFactor.h:333
typename std::tuple_element< I - 1, std::tuple< ValueTypes... > >::type ValueType
Definition: NonlinearFactor.h:525
virtual bool sendable() const
Definition: NonlinearFactor.h:176
Definition: utilities.h:49
Special class for optional Jacobian arguments.
Definition: NonlinearFactor.h:335
std::enable_if_t<(... &&std::is_convertible< Args, Matrix & >::value), Ret > AreAllMatrixRefs
Definition: NonlinearFactor.h:467
virtual shared_ptr clone() const
Definition: NonlinearFactor.h:153
NoiseModelFactor(const SharedNoiseModel &noiseModel)
Definition: NonlinearFactor.h:229
NonlinearFactor(const CONTAINER &keys)
Definition: NonlinearFactor.h:90
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
The base class for all factors.