ShonanFactor.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 #include <type_traits>
27 
28 namespace gtsam {
29 
35 template <size_t d>
36 class GTSAM_EXPORT ShonanFactor : public NoiseModelFactor2<SOn, SOn> {
38  size_t p_, pp_;
39  boost::shared_ptr<Matrix> G_;
40 
41  // Select Rot2 or Rot3 interface based template parameter d
43 
44 public:
47 
51  ShonanFactor(Key j1, Key j2, const Rot &R12, size_t p,
52  const SharedNoiseModel &model = nullptr,
53  const boost::shared_ptr<Matrix> &G = nullptr);
54 
58 
60  void
61  print(const std::string &s,
62  const KeyFormatter &keyFormatter = DefaultKeyFormatter) const override;
63 
65  bool equals(const NonlinearFactor &expected,
66  double tol = 1e-9) const override;
67 
71 
74  Vector
75  evaluateError(const SOn &Q1, const SOn &Q2,
76  boost::optional<Matrix &> H1 = boost::none,
77  boost::optional<Matrix &> H2 = boost::none) const override;
79 
80 private:
82  void fillJacobians(const Matrix &M1, const Matrix &M2,
83  boost::optional<Matrix &> H1,
84  boost::optional<Matrix &> H2) const;
85 };
86 
87 // Explicit instantiation for d=2 and d=3 in .cpp file:
90 
91 } // namespace gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
JacobiRotation< float > G
noiseModel::Diagonal::shared_ptr model
Matrix expected
Definition: testMatrix.cpp:974
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
boost::shared_ptr< Matrix > G_
matrix of vectorized generators
Definition: ShonanFactor.h:39
MatrixXf M1
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
Definition: SOn.h:50
size_t pp_
dimensionality constants
Definition: ShonanFactor.h:38
SO4 Q1
Definition: testSO4.cpp:53
Eigen::VectorXd Vector
Definition: Vector.h:38
M1<< 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12;Map< MatrixXf > M2(M1.data(), 6, 2)
SO4 Q2
Definition: testSO4.cpp:55
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
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
traits
Definition: chartTesting.h:28
Non-linear factor base classes.
float * p
const G double tol
Definition: Group.h:83
Matrix M_
measured rotation between R1 and R2
Definition: ShonanFactor.h:37
N*N matrix representation of SO(N). N can be Eigen::Dynamic.
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
2D rotation
typename std::conditional< d==2, Rot2, Rot3 >::type Rot
Definition: ShonanFactor.h:42
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
3D rotation represented as a rotation matrix or quaternion


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:44:02