GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
FrobeniusFactor.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010-2019, 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 #pragma once
20 
21 #include <gtsam/geometry/Rot2.h>
22 #include <gtsam/geometry/Rot3.h>
23 #include <gtsam/geometry/SOn.h>
25 
26 namespace gtsam {
27 
42 GTSAM_EXPORT SharedNoiseModel
43 ConvertNoiseModel(const SharedNoiseModel &model, size_t n,
44  bool defaultToUnit = true);
45 
50 template <class Rot>
51 class FrobeniusPrior : public NoiseModelFactorN<Rot> {
52  enum { Dim = Rot::VectorN2::RowsAtCompileTime };
53  using MatrixNN = typename Rot::MatrixNN;
54  Eigen::Matrix<double, Dim, 1> vecM_;
55 
56  public:
57 
58  // Provide access to the Matrix& version of evaluateError:
59  using NoiseModelFactor1<Rot>::evaluateError;
60 
61  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
62 
64  FrobeniusPrior(Key j, const MatrixNN& M,
65  const SharedNoiseModel& model = nullptr)
66  : NoiseModelFactorN<Rot>(ConvertNoiseModel(model, Dim), j) {
67  vecM_ << Eigen::Map<const Matrix>(M.data(), Dim, 1);
68  }
69 
71  Vector evaluateError(const Rot& R, OptionalMatrixType H) const override {
72  return R.vec(H) - vecM_; // Jacobian is computed only when needed.
73  }
74 };
75 
80 template <class Rot>
81 class FrobeniusFactor : public NoiseModelFactorN<Rot, Rot> {
82  enum { Dim = Rot::VectorN2::RowsAtCompileTime };
83 
84  public:
85 
86  // Provide access to the Matrix& version of evaluateError:
87  using NoiseModelFactor2<Rot, Rot>::evaluateError;
88 
90  FrobeniusFactor(Key j1, Key j2, const SharedNoiseModel& model = nullptr)
91  : NoiseModelFactorN<Rot, Rot>(ConvertNoiseModel(model, Dim), j1,
92  j2) {}
93 
95  Vector evaluateError(const Rot& R1, const Rot& R2,
96  OptionalMatrixType H1, OptionalMatrixType H2) const override {
97  Vector error = R2.vec(H2) - R1.vec(H1);
98  if (H1) *H1 = -*H1;
99  return error;
100  }
101 };
102 
109 template <class Rot>
110 class FrobeniusBetweenFactor : public NoiseModelFactorN<Rot, Rot> {
111  Rot R12_;
112  Eigen::Matrix<double, Rot::dimension, Rot::dimension>
113  R2hat_H_R1_;
114  enum { Dim = Rot::VectorN2::RowsAtCompileTime };
115 
116  public:
117 
118  // Provide access to the Matrix& version of evaluateError:
119  using NoiseModelFactor2<Rot, Rot>::evaluateError;
120 
121  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
122 
125 
127  FrobeniusBetweenFactor(Key j1, Key j2, const Rot& R12,
128  const SharedNoiseModel& model = nullptr)
129  : NoiseModelFactorN<Rot, Rot>(
130  ConvertNoiseModel(model, Dim), j1, j2),
131  R12_(R12),
132  R2hat_H_R1_(R12.inverse().AdjointMap()) {}
133 
137 
139  void
140  print(const std::string &s,
141  const KeyFormatter &keyFormatter = DefaultKeyFormatter) const override {
142  std::cout << s << "FrobeniusBetweenFactor<" << demangle(typeid(Rot).name())
143  << ">(" << keyFormatter(this->key1()) << ","
144  << keyFormatter(this->key2()) << ")\n";
145  traits<Rot>::Print(R12_, " R12: ");
146  this->noiseModel_->print(" noise model: ");
147  }
148 
150  bool equals(const NonlinearFactor &expected,
151  double tol = 1e-9) const override {
152  auto e = dynamic_cast<const FrobeniusBetweenFactor *>(&expected);
153  return e != nullptr && NoiseModelFactorN<Rot, Rot>::equals(*e, tol) &&
154  traits<Rot>::Equals(this->R12_, e->R12_, tol);
155  }
156 
160 
162  Vector evaluateError(const Rot& R1, const Rot& R2,
163  OptionalMatrixType H1, OptionalMatrixType H2) const override {
164  const Rot R2hat = R1.compose(R12_);
165  Eigen::Matrix<double, Dim, Rot::dimension> vec_H_R2hat;
166  Vector error = R2.vec(H2) - R2hat.vec(H1 ? &vec_H_R2hat : nullptr);
167  if (H1) *H1 = -vec_H_R2hat * R2hat_H_R1_;
168  return error;
169  }
171 };
172 
173 } // namespace gtsam
Definition: NonlinearFactor.h:431
double error(const Values &c) const override
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Vector evaluateError(const Rot &R1, const Rot &R2, OptionalMatrixType H1, OptionalMatrixType H2) const override
Error is just Frobenius norm between rotation matrices.
Definition: FrobeniusFactor.h:95
EIGEN_MAKE_ALIGNED_OPERATOR_NEW FrobeniusPrior(Key j, const MatrixNN &M, const SharedNoiseModel &model=nullptr)
Constructor.
Definition: FrobeniusFactor.h:64
Definition: Group.h:43
Definition: NonlinearFactor.h:68
Definition: FrobeniusFactor.h:110
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:55
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
assert equality up to a tolerance
Definition: FrobeniusFactor.h:150
std::string GTSAM_EXPORT demangle(const char *name)
Function to demangle type name of variable, e.g. demangle(typeid(x).name())
Vector evaluateError(const Rot &R, OptionalMatrixType H) const override
Error is just Frobenius norm between Rot element and vectorized matrix M.
Definition: FrobeniusFactor.h:71
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
GTSAM_EXPORT SharedNoiseModel ConvertNoiseModel(const SharedNoiseModel &model, size_t n, bool defaultToUnit=true)
Definition: FrobeniusFactor.h:81
Definition: chartTesting.h:28
Non-linear factor base classes.
FrobeniusFactor(Key j1, Key j2, const SharedNoiseModel &model=nullptr)
Constructor.
Definition: FrobeniusFactor.h:90
Vector evaluateError(const Rot &R1, const Rot &R2, OptionalMatrixType H1, OptionalMatrixType H2) const override
Error is Frobenius norm between R1*R12 and R2.
Definition: FrobeniusFactor.h:162
FrobeniusBetweenFactor(Key j1, Key j2, const Rot &R12, const SharedNoiseModel &model=nullptr)
Construct from two keys and measured rotation.
Definition: FrobeniusFactor.h:127
void print(const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print with optional string
Definition: FrobeniusFactor.h:140
N*N matrix representation of SO(N). N can be Eigen::Dynamic.
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
2D rotation
Definition: FrobeniusFactor.h:51
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
3D rotation represented as a rotation matrix or quaternion