InvDepthFactorVariant2.h
Go to the documentation of this file.
1 
12 #pragma once
13 
16 #include <gtsam/geometry/Cal3_S2.h>
17 #include <gtsam/geometry/Pose3.h>
18 #include <gtsam/geometry/Point2.h>
20 
21 namespace gtsam {
22 
26 class InvDepthFactorVariant2: public NoiseModelFactorN<Pose3, Vector3> {
27 protected:
28 
29  // Keep a copy of measurement and calibration for I/O
33 
34 public:
35 
37  typedef NoiseModelFactor2<Pose3, Vector3> Base;
38 
39  // Provide access to the Matrix& version of evaluateError:
40  using Base::evaluateError;
41 
44 
46  typedef std::shared_ptr<This> shared_ptr;
47 
50  measured_(0.0, 0.0), K_(new Cal3_S2(444, 555, 666, 777, 888)) {
51  }
52 
61  InvDepthFactorVariant2(const Key poseKey, const Key landmarkKey,
63  const SharedNoiseModel& model) :
64  Base(model, poseKey, landmarkKey), measured_(measured), K_(K), referencePoint_(referencePoint) {}
65 
68 
74  void print(const std::string& s = "InvDepthFactorVariant2",
75  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
76  Base::print(s, keyFormatter);
77  traits<Point2>::Print(measured_, s + ".z");
78  }
79 
81  bool equals(const NonlinearFactor& p, double tol = 1e-9) const override {
82  const This *e = dynamic_cast<const This*>(&p);
83  return e
84  && Base::equals(p, tol)
85  && traits<Point2>::Equals(this->measured_, e->measured_, tol)
86  && this->K_->equals(*e->K_, tol)
87  && traits<Point3>::Equals(this->referencePoint_, e->referencePoint_, tol);
88  }
89 
91  try {
92  // Calculate the 3D coordinates of the landmark in the world frame
93  double theta = landmark(0), phi = landmark(1), rho = landmark(2);
94  Point3 world_P_landmark = referencePoint_ + Point3(cos(theta)*cos(phi)/rho, sin(theta)*cos(phi)/rho, sin(phi)/rho);
95  // Project landmark into Pose2
96  PinholeCamera<Cal3_S2> camera(pose, *K_);
97  return camera.project(world_P_landmark) - measured_;
98  } catch( CheiralityException& e) {
99  std::cout << e.what()
100  << ": Inverse Depth Landmark [" << DefaultKeyFormatter(this->key<2>()) << "]"
101  << " moved behind camera [" << DefaultKeyFormatter(this->key<1>()) <<"]"
102  << std::endl;
103  return Vector::Ones(2) * 2.0 * K_->fx();
104  }
105  return (Vector(1) << 0.0).finished();
106  }
107 
110  OptionalMatrixType H1, OptionalMatrixType H2) const override {
111 
112  if (H1) {
113  (*H1) = numericalDerivative11<Vector, Pose3>(
115  std::placeholders::_1, landmark), pose);
116  }
117  if (H2) {
118  (*H2) = numericalDerivative11<Vector, Vector3>(
119  std::bind(&InvDepthFactorVariant2::inverseDepthError, this, pose,
120  std::placeholders::_1), landmark);
121  }
122 
123  return inverseDepthError(pose, landmark);
124  }
125 
127  const Point2& imagePoint() const {
128  return measured_;
129  }
130 
133  return K_;
134  }
135 
137  const Point3& referencePoint() const {
138  return referencePoint_;
139  }
140 
141 private:
142 
143 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
144  friend class boost::serialization::access;
146  template<class ARCHIVE>
147  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
148  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
149  ar & BOOST_SERIALIZATION_NVP(measured_);
150  ar & BOOST_SERIALIZATION_NVP(K_);
151  ar & BOOST_SERIALIZATION_NVP(referencePoint_);
152  }
153 #endif
154 };
155 
156 } // \ namespace gtsam
Point2 measured(-17, 30)
const gtsam::Key poseKey
Jet< T, N > cos(const Jet< T, N > &f)
Definition: jet.h:426
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
const Cal3_S2::shared_ptr calibration() const
Eigen::Vector3d Vector3
Definition: Vector.h:43
std::string serialize(const T &input)
serializes to a string
noiseModel::Diagonal::shared_ptr model
Vector2 Point2
Definition: Point2.h:32
Jet< T, N > sin(const Jet< T, N > &f)
Definition: jet.h:439
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
Some functions to compute numerical derivatives.
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
Cal3_S2::shared_ptr K_
shared pointer to calibration object
Vector evaluateError(const Pose3 &pose, const Vector3 &landmark, OptionalMatrixType H1, OptionalMatrixType H2) const override
Evaluate error h(x)-z and optionally derivatives.
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
static Point3 landmark(0, 0, 5)
Base class for all pinhole cameras.
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const
project a 3D point from world coordinates into the image
Definition: PinholePose.h:112
Matrix * OptionalMatrixType
std::shared_ptr< Cal3_S2 > shared_ptr
Definition: Cal3_S2.h:39
Vector inverseDepthError(const Pose3 &pose, const Vector3 &landmark) const
Eigen::VectorXd Vector
Definition: Vector.h:38
Point3 referencePoint_
the reference point/origin for this landmark
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
The most common 5DOF 3D->2D calibration.
Definition: Cal3_S2.h:34
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
traits
Definition: chartTesting.h:28
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Non-linear factor base classes.
InvDepthFactorVariant2()
Default constructor.
NoiseModelFactor2< Pose3, Vector3 > Base
shorthand for base class type
float * p
InvDepthFactorVariant2(const Key poseKey, const Key landmarkKey, const Point2 &measured, const Cal3_S2::shared_ptr &K, const Point3 referencePoint, const SharedNoiseModel &model)
InvDepthFactorVariant2 This
shorthand for this class
const G double tol
Definition: Group.h:86
Vector3 Point3
Definition: Point3.h:38
static const CalibratedCamera camera(kDefaultPose)
2D Point
3D Pose
const Point3 & referencePoint() const
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
Definition: Key.cpp:62
void print(const std::string &s="InvDepthFactorVariant2", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
The most common 5DOF 3D->2D calibration.
const char * what() const noexcept override


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