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 
41 GTSAM_EXPORT SharedNoiseModel
43  bool defaultToUnit = true);
44 
49 template <class T>
50 class FrobeniusPrior : public NoiseModelFactorN<T> {
51  inline constexpr static auto N = T::LieAlgebra::RowsAtCompileTime;
52  inline constexpr static auto Dim = N * N;
55 
56  public:
57 
58  // Provide access to the Matrix& version of evaluateError:
59  using NoiseModelFactor1<T>::evaluateError;
60 
62 
65  const SharedNoiseModel& model = nullptr)
67  vecM_ << Eigen::Map<const Matrix>(M.data(), Dim, 1);
68  }
69 
71  Vector evaluateError(const T& g, OptionalMatrixType H) const override {
72  return g.vec(H) - vecM_; // Jacobian is computed only when needed.
73  }
74 };
75 
80 template <class T>
81 class FrobeniusFactor : public NoiseModelFactorN<T, T> {
82  inline constexpr static auto N = T::LieAlgebra::RowsAtCompileTime;
83  inline constexpr static auto Dim = N * N;
84 
85  public:
86 
87  // Provide access to the Matrix& version of evaluateError:
88  using NoiseModelFactor2<T, T>::evaluateError;
89 
93 
95  Vector evaluateError(const T& T1, const T& T2,
96  OptionalMatrixType H1, OptionalMatrixType H2) const override {
97  Vector error = T2.vec(H2) - T1.vec(H1);
98  if (H1) *H1 = -*H1;
99  return error;
100  }
101 };
102 
109 template <class T>
111  T T12_;
114  inline constexpr static auto N = T::LieAlgebra::RowsAtCompileTime;
115  inline constexpr static auto Dim = N * N;
116 
117  public:
118 
119  // Provide access to the Matrix& version of evaluateError:
120  using NoiseModelFactor2<T, T>::evaluateError;
121 
123 
126 
128  FrobeniusBetweenFactor(Key j1, Key j2, const T& T12,
129  const SharedNoiseModel& model = nullptr)
131  T12_(T12),
132  T2hat_H_T1_(T12.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(T).name())
143  << ">(" << keyFormatter(this->key1()) << ","
144  << keyFormatter(this->key2()) << ")\n";
145  traits<T>::Print(T12_, " T12: ");
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<T, T>::equals(*e, tol) &&
154  traits<T>::Equals(this->T12_, e->T12_, tol);
155  }
156 
160 
162  Vector evaluateError(const T& T1, const T& T2,
163  OptionalMatrixType H1, OptionalMatrixType H2) const override {
164  const T T2hat = T1.compose(T12_);
166  Vector error = T2.vec(H2) - T2hat.vec(H1 ? &vec_H_T2hat : nullptr);
167  if (H1) *H1 = -vec_H_T2hat * T2hat_H_T1_;
168  return error;
169  }
171 };
172 
173 } // namespace gtsam
SOn.h
N*N matrix representation of SO(N). N can be Eigen::Dynamic.
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::FrobeniusFactor::FrobeniusFactor
FrobeniusFactor(Key j1, Key j2, const SharedNoiseModel &model=nullptr)
Constructor.
Definition: FrobeniusFactor.h:91
inverse
const EIGEN_DEVICE_FUNC InverseReturnType inverse() const
Definition: ArrayCwiseUnaryOps.h:411
gtsam::FrobeniusPrior::evaluateError
Vector evaluateError(const T &g, OptionalMatrixType H) const override
Error is just Frobenius norm between T element and vectorized matrix M.
Definition: FrobeniusFactor.h:71
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::FrobeniusFactor::Dim
constexpr static auto Dim
Definition: FrobeniusFactor.h:83
gtsam::NoiseModelFactor::error
double error(const Values &c) const override
Definition: NonlinearFactor.cpp:138
gtsam::FrobeniusBetweenFactor::evaluateError
Vector evaluateError(const T &T1, const T &T2, OptionalMatrixType H1, OptionalMatrixType H2) const override
Error is Frobenius norm between T1*T12 and T2.
Definition: FrobeniusFactor.h:162
gtsam::FrobeniusPrior::N
constexpr static auto N
Definition: FrobeniusFactor.h:51
gtsam::FrobeniusFactor
Definition: FrobeniusFactor.h:81
gtsam::FrobeniusBetweenFactor::Dim
constexpr static auto Dim
Definition: FrobeniusFactor.h:115
gtsam::FrobeniusBetweenFactor::T12_
T T12_
measured rotation between T1 and T2
Definition: FrobeniusFactor.h:111
gtsam::NoiseModelFactor::noiseModel_
SharedNoiseModel noiseModel_
Definition: NonlinearFactor.h:206
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
Rot2.h
2D rotation
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
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
n
int n
Definition: BiCGSTAB_simple.cpp:1
gtsam::FrobeniusPrior::FrobeniusPrior
EIGEN_MAKE_ALIGNED_OPERATOR_NEW FrobeniusPrior(Key j, const MatrixNN &M, const SharedNoiseModel &model=nullptr)
Constructor.
Definition: FrobeniusFactor.h:64
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:50
gtsam::NoiseModelFactorN
Definition: NonlinearFactor.h:434
cholesky::expected
Matrix expected
Definition: testMatrix.cpp:916
gtsam::NoiseModelFactor::equals
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Definition: NonlinearFactor.cpp:82
T2
static const Pose3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2)
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:762
Eigen::Triplet< double >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW
Definition: Memory.h:841
gtsam::NoiseModelFactorN< T, T >::key1
Key key1() const
Definition: NonlinearFactor.h:734
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
g
void g(const string &key, int i)
Definition: testBTree.cpp:41
gtsam::FrobeniusBetweenFactor::N
constexpr static auto N
Definition: FrobeniusFactor.h:114
gtsam::ConvertNoiseModel
SharedNoiseModel ConvertNoiseModel(const SharedNoiseModel &model, size_t d, bool defaultToUnit)
Definition: FrobeniusFactor.cpp:27
NonlinearFactor.h
Non-linear factor base classes.
gtsam::NoiseModelFactorN< T, T >::key2
Key key2() const
Definition: NonlinearFactor.h:738
gtsam::FrobeniusFactor::N
constexpr static auto N
Definition: FrobeniusFactor.h:82
gtsam
traits
Definition: SFMdata.h:40
gtsam::FrobeniusPrior::Dim
constexpr static auto Dim
Definition: FrobeniusFactor.h:52
gtsam::traits
Definition: Group.h:36
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::FrobeniusFactor::evaluateError
Vector evaluateError(const T &T1, const T &T2, OptionalMatrixType H1, OptionalMatrixType H2) const override
Error is just Frobenius norm between rotation matrices.
Definition: FrobeniusFactor.h:95
gtsam::FrobeniusBetweenFactor::T2hat_H_T1_
Eigen::Matrix< double, T::dimension, T::dimension > T2hat_H_T1_
fixed derivative of T2hat wrpt T1
Definition: FrobeniusFactor.h:113
gtsam::demangle
std::string demangle(const char *name)
Pretty print Value type name.
Definition: types.cpp:37
gtsam::NonlinearFactor
Definition: NonlinearFactor.h:69
gtsam::Print
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
Definition: Key.cpp:65
gtsam::FrobeniusPrior::vecM_
Eigen::Matrix< double, Dim, 1 > vecM_
vectorized matrix to approximate
Definition: FrobeniusFactor.h:54
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::OptionalMatrixType
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:56
Eigen::Matrix< double, N, N >
gtsam::FrobeniusBetweenFactor::FrobeniusBetweenFactor
FrobeniusBetweenFactor(Key j1, Key j2, const T &T12, const SharedNoiseModel &model=nullptr)
Construct from two keys and measured rotation.
Definition: FrobeniusFactor.h:128
T1
static const Similarity3 T1(R, Point3(3.5, -8.2, 4.2), 1)
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
j1
double j1(double x)
Definition: j1.c:174
gtsam::FrobeniusBetweenFactor::print
void print(const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print with optional string
Definition: FrobeniusFactor.h:140
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51


gtsam
Author(s):
autogenerated on Wed Mar 19 2025 03:01:40