InvDepthFactorVariant1.h
Go to the documentation of this file.
1 
11 #pragma once
12 
15 #include <gtsam/geometry/Cal3_S2.h>
16 #include <gtsam/geometry/Pose3.h>
17 #include <gtsam/geometry/Point2.h>
19 
20 namespace gtsam {
21 
25 class InvDepthFactorVariant1: public NoiseModelFactorN<Pose3, Vector6> {
26 protected:
27 
28  // Keep a copy of measurement and calibration for I/O
31 
32 public:
33 
35  typedef NoiseModelFactor2<Pose3, Vector6> Base;
36 
37  // Provide access to the Matrix& version of evaluateError:
38  using Base::evaluateError;
39 
42 
44  typedef std::shared_ptr<This> shared_ptr;
45 
48  measured_(0.0, 0.0), K_(new Cal3_S2(444, 555, 666, 777, 888)) {
49  }
50 
59  InvDepthFactorVariant1(const Key poseKey, const Key landmarkKey,
60  const Point2& measured, const Cal3_S2::shared_ptr& K, const SharedNoiseModel& model) :
61  Base(model, poseKey, landmarkKey), measured_(measured), K_(K) {}
62 
65 
71  void print(const std::string& s = "InvDepthFactorVariant1",
72  const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
73  Base::print(s, keyFormatter);
74  traits<Point2>::Print(measured_, s + ".z");
75  }
76 
78  bool equals(const NonlinearFactor& p, double tol = 1e-9) const override {
79  const This *e = dynamic_cast<const This*>(&p);
80  return e
81  && Base::equals(p, tol)
82  && traits<Point2>::Equals(this->measured_, e->measured_, tol)
83  && this->K_->equals(*e->K_, tol);
84  }
85 
86  Vector inverseDepthError(const Pose3& pose, const Vector6& landmark) const {
87  try {
88  // Calculate the 3D coordinates of the landmark in the world frame
89  double x = landmark(0), y = landmark(1), z = landmark(2);
90  double theta = landmark(3), phi = landmark(4), rho = landmark(5);
91  Point3 world_P_landmark = Point3(x, y, z) + Point3(cos(theta)*cos(phi)/rho, sin(theta)*cos(phi)/rho, sin(phi)/rho);
92  // Project landmark into Pose2
93  PinholeCamera<Cal3_S2> camera(pose, *K_);
94  return camera.project(world_P_landmark) - measured_;
95  } catch( CheiralityException& e) {
96  std::cout << e.what()
97  << ": Inverse Depth Landmark [" << DefaultKeyFormatter(this->key<2>()) << "]"
98  << " moved behind camera [" << DefaultKeyFormatter(this->key<1>()) <<"]"
99  << std::endl;
100  return Vector::Ones(2) * 2.0 * K_->fx();
101  }
102  return (Vector(1) << 0.0).finished();
103  }
104 
106  Vector evaluateError(const Pose3& pose, const Vector6& landmark,
107  OptionalMatrixType H1, OptionalMatrixType H2) const override {
108 
109  if (H1) {
110  (*H1) = numericalDerivative11<Vector, Pose3>(
112  std::placeholders::_1, landmark),
113  pose);
114  }
115  if (H2) {
116  (*H2) = numericalDerivative11<Vector, Vector6>(
117  std::bind(&InvDepthFactorVariant1::inverseDepthError, this, pose,
118  std::placeholders::_1), landmark);
119  }
120 
121  return inverseDepthError(pose, landmark);
122  }
123 
125  const Point2& imagePoint() const {
126  return measured_;
127  }
128 
131  return K_;
132  }
133 
134 private:
135 
136 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
137  friend class boost::serialization::access;
139  template<class ARCHIVE>
140  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
141  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
142  ar & BOOST_SERIALIZATION_NVP(measured_);
143  ar & BOOST_SERIALIZATION_NVP(K_);
144  }
145 #endif
146 };
147 
148 } // \ namespace gtsam
Point2 measured(-17, 30)
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
const gtsam::Key poseKey
Jet< T, N > cos(const Jet< T, N > &f)
Definition: jet.h:426
Scalar * y
std::string serialize(const T &input)
serializes to a string
InvDepthFactorVariant1()
Default constructor.
noiseModel::Diagonal::shared_ptr model
Vector2 Point2
Definition: Point2.h:32
Vector evaluateError(const Pose3 &pose, const Vector6 &landmark, OptionalMatrixType H1, OptionalMatrixType H2) const override
Evaluate error h(x)-z and optionally derivatives.
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)
void print(const std::string &s="InvDepthFactorVariant1", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Some functions to compute numerical derivatives.
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
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
Eigen::VectorXd Vector
Definition: Vector.h:38
Vector inverseDepthError(const Pose3 &pose, const Vector6 &landmark) const
InvDepthFactorVariant1 This
shorthand for this class
NoiseModelFactor2< Pose3, Vector6 > Base
shorthand for base class type
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
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
const Cal3_S2::shared_ptr calibration() const
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Non-linear factor base classes.
Cal3_S2::shared_ptr K_
shared pointer to calibration object
float * p
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
const G double tol
Definition: Group.h:86
Vector3 Point3
Definition: Point3.h:38
static const CalibratedCamera camera(kDefaultPose)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
2D Point
3D Pose
InvDepthFactorVariant1(const Key poseKey, const Key landmarkKey, const Point2 &measured, const Cal3_S2::shared_ptr &K, const SharedNoiseModel &model)
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
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