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
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;
55 
56  public:
57 
58  // Provide access to the Matrix& version of evaluateError:
59  using NoiseModelFactor1<Rot>::evaluateError;
60 
62 
65  const SharedNoiseModel& model = nullptr)
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 
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> {
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 
122 
125 
128  const SharedNoiseModel& model = nullptr)
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 
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_);
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
SOn.h
N*N matrix representation of SO(N). N can be Eigen::Dynamic.
gtsam::FrobeniusPrior::vecM_
Eigen::Matrix< double, Dim, 1 > vecM_
vectorized matrix to approximate
Definition: FrobeniusFactor.h:54
H
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
Definition: gnuplot_common_settings.hh:74
gtsam::FrobeniusPrior::MatrixNN
typename Rot::MatrixNN MatrixNN
Definition: FrobeniusFactor.h:53
inverse
const EIGEN_DEVICE_FUNC InverseReturnType inverse() const
Definition: ArrayCwiseUnaryOps.h:411
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::NoiseModelFactor::error
double error(const Values &c) const override
Definition: NonlinearFactor.cpp:136
gtsam::FrobeniusBetweenFactor::evaluateError
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
gtsam::FrobeniusFactor
Definition: FrobeniusFactor.h:81
gtsam::FrobeniusBetweenFactor::equals
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
assert equality up to a tolerance
Definition: FrobeniusFactor.h:150
gtsam::FrobeniusBetweenFactor::FrobeniusBetweenFactor
FrobeniusBetweenFactor(Key j1, Key j2, const Rot &R12, const SharedNoiseModel &model=nullptr)
Construct from two keys and measured rotation.
Definition: FrobeniusFactor.h:127
gtsam::FrobeniusFactor::FrobeniusFactor
FrobeniusFactor(Key j1, Key j2, const SharedNoiseModel &model=nullptr)
Constructor.
Definition: FrobeniusFactor.h:90
gtsam::FrobeniusPrior::FrobeniusPrior
EIGEN_MAKE_ALIGNED_OPERATOR_NEW FrobeniusPrior(Key j, const MatrixNN &M, const SharedNoiseModel &model=nullptr)
Constructor.
Definition: FrobeniusFactor.h:64
gtsam::FrobeniusFactor::Dim
@ Dim
Definition: FrobeniusFactor.h:82
gtsam::NoiseModelFactor::noiseModel_
SharedNoiseModel noiseModel_
Definition: NonlinearFactor.h:205
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
Rot
typename std::conditional< d==2, Rot2, Rot3 >::type Rot
Definition: testShonanAveraging.cpp:34
Rot2.h
2D rotation
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::FrobeniusBetweenFactor::R12_
Rot R12_
measured rotation between R1 and R2
Definition: FrobeniusFactor.h:111
name
static char name[]
Definition: rgamma.c:72
Rot3.h
3D rotation represented as a rotation matrix or quaternion
gtsam::FrobeniusBetweenFactor
Definition: FrobeniusFactor.h:110
so3::R1
SO3 R1
Definition: testShonanFactor.cpp:41
n
int n
Definition: BiCGSTAB_simple.cpp:1
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
gtsam::KeyFormatter
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::FrobeniusPrior
Definition: FrobeniusFactor.h:51
gtsam::NoiseModelFactorN
Definition: NonlinearFactor.h:431
gtsam::FrobeniusFactor::evaluateError
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
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:971
gtsam::NoiseModelFactor::equals
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Definition: NonlinearFactor.cpp:80
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW
Definition: Memory.h:841
gtsam::NoiseModelFactorN< Rot, Rot >::key1
Key key1() const
Definition: NonlinearFactor.h:731
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
gtsam::ConvertNoiseModel
SharedNoiseModel ConvertNoiseModel(const SharedNoiseModel &model, size_t d, bool defaultToUnit)
Definition: FrobeniusFactor.cpp:27
gtsam::FrobeniusBetweenFactor::R2hat_H_R1_
Eigen::Matrix< double, Rot::dimension, Rot::dimension > R2hat_H_R1_
fixed derivative of R2hat wrpt R1
Definition: FrobeniusFactor.h:113
NonlinearFactor.h
Non-linear factor base classes.
gtsam::FrobeniusBetweenFactor::Dim
@ Dim
Definition: FrobeniusFactor.h:114
gtsam::NoiseModelFactorN< Rot, Rot >::key2
Key key2() const
Definition: NonlinearFactor.h:735
gtsam::FrobeniusPrior::Dim
@ Dim
Definition: FrobeniusFactor.h:52
so3::R2
SO3 R2
Definition: testShonanFactor.cpp:43
gtsam
traits
Definition: chartTesting.h:28
gtsam::FrobeniusPrior::evaluateError
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
gtsam::traits
Definition: Group.h:36
gtsam::demangle
std::string demangle(const char *name)
Pretty print Value type name.
Definition: types.cpp:37
gtsam::NonlinearFactor
Definition: NonlinearFactor.h:68
gtsam::Print
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
Definition: Key.cpp:65
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::FrobeniusBetweenFactor::print
void print(const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print with optional string
Definition: FrobeniusFactor.h:140
gtsam::OptionalMatrixType
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:55
Eigen::Matrix< double, Dim, 1 >
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
j1
double j1(double x)
Definition: j1.c:174
so3::R12
SO3 R12
Definition: testShonanFactor.cpp:44
R
Rot2 R(Rot2::fromAngle(0.1))
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51


gtsam
Author(s):
autogenerated on Thu Jun 13 2024 03:02:21