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 NoiseModelFactor2<Pose3, Pose3> {
31 
32 private:
33 
36 
39 public:
40 
41  // shorthand for a smart pointer to a factor
42  typedef boost::shared_ptr<EssentialMatrixConstraint> shared_ptr;
43 
46  }
47 
56  const EssentialMatrix& measuredE, const SharedNoiseModel& model) :
57  Base(model, key1, key2), measuredE_(measuredE) {
58  }
59 
61  }
62 
65  return boost::static_pointer_cast<gtsam::NonlinearFactor>(
67  }
68 
72  void print(const std::string& s = "",
73  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override;
74 
76  bool equals(const NonlinearFactor& expected, double tol = 1e-9) const override;
77 
81  Vector evaluateError(const Pose3& p1, const Pose3& p2,
82  boost::optional<Matrix&> Hp1 = boost::none, //
83  boost::optional<Matrix&> Hp2 = boost::none) const override;
84 
86  const EssentialMatrix& measured() const {
87  return measuredE_;
88  }
89 
90 private:
91 
93  friend class boost::serialization::access;
94  template<class ARCHIVE>
95  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
96  ar
97  & boost::serialization::make_nvp("NoiseModelFactor2",
98  boost::serialization::base_object<Base>(*this));
99  ar & BOOST_SERIALIZATION_NVP(measuredE_);
100  }
101 
102 public:
104 };
105 // \class EssentialMatrixConstraint
106 
107 }
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
boost::shared_ptr< EssentialMatrixConstraint > shared_ptr
Vector3f p1
noiseModel::Diagonal::shared_ptr model
Matrix expected
Definition: testMatrix.cpp:974
const EssentialMatrix & measured() const
void serialize(ARCHIVE &ar, const unsigned int)
EssentialMatrixConstraint(Key key1, Key key2, const EssentialMatrix &measuredE, const SharedNoiseModel &model)
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
NoiseModelFactor2< Pose3, Pose3 > Base
const Symbol key1('v', 1)
Eigen::VectorXd Vector
Definition: Vector.h:38
boost::shared_ptr< This > shared_ptr
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
#define This
traits
Definition: chartTesting.h:28
Non-linear factor base classes.
const Symbol key2('v', 2)
static Point3 p2
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:269
const G double tol
Definition: Group.h:83
gtsam::NonlinearFactor::shared_ptr clone() const override
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734


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