EssentialMatrixConstraint.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010-2014, 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 
23 
24 namespace gtsam {
25 
30 class GTSAM_EXPORT EssentialMatrixConstraint: public NoiseModelFactorN<Pose3, Pose3> {
31 
32 private:
33 
36 
39 public:
40 
41  // Provide access to the Matrix& version of evaluateError:
42  using Base::evaluateError;
43 
44  // shorthand for a smart pointer to a factor
45  typedef std::shared_ptr<EssentialMatrixConstraint> shared_ptr;
46 
49  }
50 
59  const EssentialMatrix& measuredE, const SharedNoiseModel& model) :
60  Base(model, key1, key2), measuredE_(measuredE) {
61  }
62 
64  }
65 
68  return std::static_pointer_cast<gtsam::NonlinearFactor>(
70  }
71 
75  void print(const std::string& s = "",
76  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override;
77 
79  bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;
80 
84  Vector evaluateError(const Pose3& p1, const Pose3& p2,
85  OptionalMatrixType Hp1, OptionalMatrixType Hp2) const override;
86 
88  const EssentialMatrix& measured() const {
89  return measuredE_;
90  }
91 
92 private:
93 
94 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
95 
96  friend class boost::serialization::access;
97  template<class ARCHIVE>
98  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
99  // NoiseModelFactor2 instead of NoiseModelFactorN for backward compatibility
100  ar
101  & boost::serialization::make_nvp("NoiseModelFactor2",
102  boost::serialization::base_object<Base>(*this));
103  ar & BOOST_SERIALIZATION_NVP(measuredE_);
104  }
105 #endif
106 
107 public:
109 };
110 // \class EssentialMatrixConstraint
111 
112 }
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
Vector3f p1
std::string serialize(const T &input)
serializes to a string
noiseModel::Diagonal::shared_ptr model
Matrix expected
Definition: testMatrix.cpp:971
EssentialMatrixConstraint(Key key1, Key key2, const EssentialMatrix &measuredE, const SharedNoiseModel &model)
std::shared_ptr< EssentialMatrixConstraint > shared_ptr
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
Matrix * OptionalMatrixType
Eigen::VectorXd Vector
Definition: Vector.h:38
const Symbol key1('v', 1)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
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
#define This
const EssentialMatrix & measured() const
traits
Definition: chartTesting.h:28
Non-linear factor base classes.
std::shared_ptr< This > shared_ptr
static Point3 p2
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:284
const G double tol
Definition: Group.h:86
gtsam::NonlinearFactor::shared_ptr clone() const override
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
NoiseModelFactorN< Pose3, Pose3 > Base
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
const Symbol key2('v', 2)


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:34:12