gtsam 4.1.1
gtsam
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
26namespace gtsam {
27
42GTSAM_EXPORT SharedNoiseModel
43ConvertNoiseModel(const SharedNoiseModel &model, size_t n,
44 bool defaultToUnit = true);
45
50template <class Rot>
51class GTSAM_EXPORT FrobeniusPrior : public NoiseModelFactor1<Rot> {
52 enum { Dim = Rot::VectorN2::RowsAtCompileTime };
53 using MatrixNN = typename Rot::MatrixNN;
54 Eigen::Matrix<double, Dim, 1> vecM_;
55
56 public:
58 FrobeniusPrior(Key j, const MatrixNN& M,
59 const SharedNoiseModel& model = nullptr)
60 : NoiseModelFactor1<Rot>(ConvertNoiseModel(model, Dim), j) {
61 vecM_ << Eigen::Map<const Matrix>(M.data(), Dim, 1);
62 }
63
65 Vector evaluateError(const Rot& R,
66 boost::optional<Matrix&> H = boost::none) const override {
67 return R.vec(H) - vecM_; // Jacobian is computed only when needed.
68 }
69};
70
75template <class Rot>
76class GTSAM_EXPORT FrobeniusFactor : public NoiseModelFactor2<Rot, Rot> {
77 enum { Dim = Rot::VectorN2::RowsAtCompileTime };
78
79 public:
81 FrobeniusFactor(Key j1, Key j2, const SharedNoiseModel& model = nullptr)
82 : NoiseModelFactor2<Rot, Rot>(ConvertNoiseModel(model, Dim), j1,
83 j2) {}
84
86 Vector evaluateError(const Rot& R1, const Rot& R2,
87 boost::optional<Matrix&> H1 = boost::none,
88 boost::optional<Matrix&> H2 = boost::none) const override {
89 Vector error = R2.vec(H2) - R1.vec(H1);
90 if (H1) *H1 = -*H1;
91 return error;
92 }
93};
94
101template <class Rot>
102class GTSAM_EXPORT FrobeniusBetweenFactor : public NoiseModelFactor2<Rot, Rot> {
103 Rot R12_;
104 Eigen::Matrix<double, Rot::dimension, Rot::dimension>
105 R2hat_H_R1_;
106 enum { Dim = Rot::VectorN2::RowsAtCompileTime };
107
108 public:
111
113 FrobeniusBetweenFactor(Key j1, Key j2, const Rot& R12,
114 const SharedNoiseModel& model = nullptr)
115 : NoiseModelFactor2<Rot, Rot>(
116 ConvertNoiseModel(model, Dim), j1, j2),
117 R12_(R12),
118 R2hat_H_R1_(R12.inverse().AdjointMap()) {}
119
123
125 void
126 print(const std::string &s,
127 const KeyFormatter &keyFormatter = DefaultKeyFormatter) const override {
128 std::cout << s << "FrobeniusBetweenFactor<" << demangle(typeid(Rot).name())
129 << ">(" << keyFormatter(this->key1()) << ","
130 << keyFormatter(this->key2()) << ")\n";
131 traits<Rot>::Print(R12_, " R12: ");
132 this->noiseModel_->print(" noise model: ");
133 }
134
136 bool equals(const NonlinearFactor &expected,
137 double tol = 1e-9) const override {
138 auto e = dynamic_cast<const FrobeniusBetweenFactor *>(&expected);
139 return e != nullptr && NoiseModelFactor2<Rot, Rot>::equals(*e, tol) &&
140 traits<Rot>::Equals(this->R12_, e->R12_, tol);
141 }
142
146
148 Vector evaluateError(const Rot& R1, const Rot& R2,
149 boost::optional<Matrix&> H1 = boost::none,
150 boost::optional<Matrix&> H2 = boost::none) const override {
151 const Rot R2hat = R1.compose(R12_);
152 Eigen::Matrix<double, Dim, Rot::dimension> vec_H_R2hat;
153 Vector error = R2.vec(H2) - R2hat.vec(H1 ? &vec_H_R2hat : nullptr);
154 if (H1) *H1 = -vec_H_R2hat * R2hat_H_R1_;
155 return error;
156 }
158};
159
160} // namespace gtsam
N*N matrix representation of SO(N).
2D rotation
3D rotation represented as a rotation matrix or quaternion
Non-linear factor base classes.
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
std::string demangle(const char *name)
Pretty print Value type name.
Definition: types.cpp:37
SharedNoiseModel ConvertNoiseModel(const SharedNoiseModel &model, size_t d, bool defaultToUnit)
When creating (any) FrobeniusFactor we can convert a Rot/Pose BetweenFactor noise model into a n-dime...
Definition: FrobeniusFactor.cpp:27
noiseModel::Base::shared_ptr SharedNoiseModel
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:736
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:69
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
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
Nonlinear factor base class.
Definition: NonlinearFactor.h:43
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Check if two factors are equal.
Definition: NonlinearFactor.cpp:71
A convenient base class for creating your own NoiseModelFactor with 1 variable.
Definition: NonlinearFactor.h:285
A convenient base class for creating your own NoiseModelFactor with 2 variables.
Definition: NonlinearFactor.h:369
FrobeniusPrior calculates the Frobenius norm between a given matrix and an element of SO(3) or SO(4).
Definition: FrobeniusFactor.h:51
FrobeniusPrior(Key j, const MatrixNN &M, const SharedNoiseModel &model=nullptr)
Constructor.
Definition: FrobeniusFactor.h:58
Vector evaluateError(const Rot &R, boost::optional< Matrix & > H=boost::none) const override
Error is just Frobenius norm between Rot element and vectorized matrix M.
Definition: FrobeniusFactor.h:65
FrobeniusFactor calculates the Frobenius norm between rotation matrices.
Definition: FrobeniusFactor.h:76
Vector evaluateError(const Rot &R1, const Rot &R2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
Error is just Frobenius norm between rotation matrices.
Definition: FrobeniusFactor.h:86
FrobeniusFactor(Key j1, Key j2, const SharedNoiseModel &model=nullptr)
Constructor.
Definition: FrobeniusFactor.h:81
FrobeniusBetweenFactor is a BetweenFactor that evaluates the Frobenius norm of the rotation error bet...
Definition: FrobeniusFactor.h:102
FrobeniusBetweenFactor(Key j1, Key j2, const Rot &R12, const SharedNoiseModel &model=nullptr)
Construct from two keys and measured rotation.
Definition: FrobeniusFactor.h:113
void print(const std::string &s, const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print with optional string
Definition: FrobeniusFactor.h:126
Vector evaluateError(const Rot &R1, const Rot &R2, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
Error is Frobenius norm between R1*R12 and R2.
Definition: FrobeniusFactor.h:148
bool equals(const NonlinearFactor &expected, double tol=1e-9) const override
assert equality up to a tolerance
Definition: FrobeniusFactor.h:136