StereoFactor.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, 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 <optional>
24 
25 namespace gtsam {
26 
31 template<class POSE, class LANDMARK>
32 class GenericStereoFactor: public NoiseModelFactorN<POSE, LANDMARK> {
33 private:
34 
35  // Keep a copy of measurement and calibration for I/O
38  std::optional<POSE> body_P_sensor_;
39 
40  // verbosity handling for Cheirality Exceptions
43 
44 public:
45 
46  // shorthand for base class type
49  typedef std::shared_ptr<GenericStereoFactor> shared_ptr;
50  typedef POSE CamPose;
51 
52  // Provide access to the Matrix& version of evaluateError:
53  using Base::evaluateError;
54 
58  GenericStereoFactor() : K_(new Cal3_S2Stereo(444, 555, 666, 777, 888, 1.0)),
59  throwCheirality_(false), verboseCheirality_(false) {}
60 
71  Key poseKey, Key landmarkKey, const Cal3_S2Stereo::shared_ptr& K,
72  std::optional<POSE> body_P_sensor = {}) :
74  throwCheirality_(false), verboseCheirality_(false) {}
75 
88  Key poseKey, Key landmarkKey, const Cal3_S2Stereo::shared_ptr& K,
90  std::optional<POSE> body_P_sensor = {}) :
93 
95  ~GenericStereoFactor() override {}
96 
99  return std::static_pointer_cast<gtsam::NonlinearFactor>(
101 
107  void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
108  Base::print(s, keyFormatter);
109  measured_.print(s + ".z");
110  if(this->body_P_sensor_)
111  this->body_P_sensor_->print(" sensor pose in body frame: ");
112  }
113 
117  bool equals(const NonlinearFactor& f, double tol = 1e-9) const override {
118  const GenericStereoFactor* e = dynamic_cast<const GenericStereoFactor*> (&f);
119  return e
120  && Base::equals(f)
121  && measured_.equals(e->measured_, tol)
122  && ((!body_P_sensor_ && !e->body_P_sensor_) || (body_P_sensor_ && e->body_P_sensor_ && body_P_sensor_->equals(*e->body_P_sensor_)));
123  }
124 
127  OptionalMatrixType H1, OptionalMatrixType H2) const override {
128  try {
129  if(body_P_sensor_) {
130  if(H1) {
131  gtsam::Matrix H0;
132  StereoCamera stereoCam(pose.compose(*body_P_sensor_, H0), K_);
133  StereoPoint2 reprojectionError(stereoCam.project(point, H1, H2) - measured_);
134  *H1 = *H1 * H0;
135  return reprojectionError.vector();
136  } else {
138  return (stereoCam.project(point, H1, H2) - measured_).vector();
139  }
140  } else {
142  return (stereoCam.project(point, H1, H2) - measured_).vector();
143  }
144  } catch(StereoCheiralityException& e) {
145  if (H1) *H1 = Matrix::Zero(3,6);
146  if (H2) *H2 = Z_3x3;
147  if (verboseCheirality_)
148  std::cout << e.what() << ": Landmark "<< DefaultKeyFormatter(this->key2()) <<
149  " moved behind camera " << DefaultKeyFormatter(this->key1()) << std::endl;
150  if (throwCheirality_)
151  throw StereoCheiralityException(this->key2());
152  }
153  return Vector3::Constant(2.0 * K_->fx());
154  }
155 
157  const StereoPoint2& measured() const {
158  return measured_;
159  }
160 
162  inline const Cal3_S2Stereo::shared_ptr calibration() const {
163  return K_;
164  }
165 
167  inline bool verboseCheirality() const { return verboseCheirality_; }
168 
170  inline bool throwCheirality() const { return throwCheirality_; }
171 
173  const std::optional<POSE>& body_P_sensor() const {
174  return body_P_sensor_;
175  }
176 
177 private:
178 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
179 
180  friend class boost::serialization::access;
181  template<class Archive>
182  void serialize(Archive & ar, const unsigned int /*version*/) {
183  // NoiseModelFactor2 instead of NoiseModelFactorN for backward compatibility
184  ar & boost::serialization::make_nvp("NoiseModelFactor2",
185  boost::serialization::base_object<Base>(*this));
186  ar & BOOST_SERIALIZATION_NVP(measured_);
187  ar & BOOST_SERIALIZATION_NVP(K_);
188  ar & BOOST_SERIALIZATION_NVP(body_P_sensor_);
189  ar & BOOST_SERIALIZATION_NVP(throwCheirality_);
190  ar & BOOST_SERIALIZATION_NVP(verboseCheirality_);
191  }
192 #endif
193 };
194 
196 template<class T1, class T2>
197 struct traits<GenericStereoFactor<T1, T2> > : public Testable<GenericStereoFactor<T1, T2> > {};
198 
199 } // \ namespace gtsam
gtsam::StereoPoint2::print
void print(const std::string &s="") const
Definition: StereoPoint2.cpp:26
gtsam::NonlinearFactor::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: NonlinearFactor.h:78
gtsam::StereoPoint2::vector
Vector3 vector() const
Definition: StereoPoint2.h:119
pose
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
gtsam::GenericStereoFactor::GenericStereoFactor
GenericStereoFactor()
Definition: StereoFactor.h:58
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::GenericStereoFactor::equals
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Definition: StereoFactor.h:117
gtsam::GenericStereoFactor::throwCheirality_
bool throwCheirality_
If true, rethrows Cheirality exceptions (default: false)
Definition: StereoFactor.h:41
gtsam::GenericStereoFactor::measured
const StereoPoint2 & measured() const
Definition: StereoFactor.h:157
stereoCam
static StereoCamera stereoCam(camPose, K)
gtsam::NoiseModelFactorN< POSE, LANDMARK >::evaluateError
virtual Vector evaluateError(const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
gtsam::GenericStereoFactor::Base
NoiseModelFactorN< POSE, LANDMARK > Base
typedef for base class
Definition: StereoFactor.h:47
gtsam::GenericStereoFactor::GenericStereoFactor
GenericStereoFactor(const StereoPoint2 &measured, const SharedNoiseModel &model, Key poseKey, Key landmarkKey, const Cal3_S2Stereo::shared_ptr &K, std::optional< POSE > body_P_sensor={})
Definition: StereoFactor.h:70
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::GenericStereoFactor::throwCheirality
bool throwCheirality() const
Definition: StereoFactor.h:170
gtsam::GenericStereoFactor::GenericStereoFactor
GenericStereoFactor(const StereoPoint2 &measured, const SharedNoiseModel &model, Key poseKey, Key landmarkKey, const Cal3_S2Stereo::shared_ptr &K, bool throwCheirality, bool verboseCheirality, std::optional< POSE > body_P_sensor={})
Definition: StereoFactor.h:87
gtsam::GenericStereoFactor
Definition: StereoFactor.h:32
gtsam::StereoPoint2::equals
bool equals(const StereoPoint2 &q, double tol=1e-9) const
Definition: StereoPoint2.h:68
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
gtsam::GenericStereoFactor::shared_ptr
std::shared_ptr< GenericStereoFactor > shared_ptr
typedef for shared pointer to this object
Definition: StereoFactor.h:49
poseKey
const gtsam::Key poseKey
Definition: testPoseRotationPrior.cpp:29
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::GenericStereoFactor::verboseCheirality_
bool verboseCheirality_
If true, prints text for Cheirality exceptions (default: false)
Definition: StereoFactor.h:42
gtsam::GenericStereoFactor::This
GenericStereoFactor< POSE, LANDMARK > This
typedef for this class (with templates)
Definition: StereoFactor.h:48
gtsam::GenericStereoFactor::evaluateError
Vector evaluateError(const Pose3 &pose, const Point3 &point, OptionalMatrixType H1, OptionalMatrixType H2) const override
Definition: StereoFactor.h:126
gtsam_unstable.tests.test_ProjectionFactorRollingShutter.point
point
Definition: test_ProjectionFactorRollingShutter.py:25
gtsam::KeyFormatter
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
gtsam::Pose3
Definition: Pose3.h:37
gtsam::GenericStereoFactor::CamPose
POSE CamPose
typedef for Pose Lie Value type
Definition: StereoFactor.h:50
gtsam::NoiseModelFactorN
Definition: NonlinearFactor.h:431
gtsam::GenericStereoFactor::calibration
const Cal3_S2Stereo::shared_ptr calibration() const
Definition: StereoFactor.h:162
gtsam::NoiseModelFactor::print
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: NonlinearFactor.cpp:72
gtsam::GenericStereoFactor::verboseCheirality
bool verboseCheirality() const
Definition: StereoFactor.h:167
gtsam::GenericStereoFactor::body_P_sensor_
std::optional< POSE > body_P_sensor_
The pose of the sensor in the body frame.
Definition: StereoFactor.h:38
gtsam::Cal3_S2Stereo::shared_ptr
std::shared_ptr< Cal3_S2Stereo > shared_ptr
Definition: Cal3_S2Stereo.h:38
gtsam::GenericStereoFactor::body_P_sensor
const std::optional< POSE > & body_P_sensor() const
Definition: StereoFactor.h:173
gtsam::NoiseModelFactor::equals
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Definition: NonlinearFactor.cpp:80
gtsam::GenericStereoFactor::measured_
StereoPoint2 measured_
the measurement
Definition: StereoFactor.h:36
T2
static const Pose3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2)
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:762
gtsam::NoiseModelFactorN< POSE, LANDMARK >::key1
Key key1() const
Definition: NonlinearFactor.h:731
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
gtsam::GenericStereoFactor::~GenericStereoFactor
~GenericStereoFactor() override
Definition: StereoFactor.h:95
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
NonlinearFactor.h
Non-linear factor base classes.
gtsam::NoiseModelFactorN< POSE, LANDMARK >::key2
Key key2() const
Definition: NonlinearFactor.h:735
gtsam
traits
Definition: SFMdata.h:40
gtsam::Testable
Definition: Testable.h:152
gtsam::Cal3_S2Stereo
The most common 5DOF 3D->2D calibration, stereo version.
Definition: Cal3_S2Stereo.h:30
gtsam::traits
Definition: Group.h:36
K
#define K
Definition: igam.h:8
gtsam::GenericStereoFactor::print
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: StereoFactor.h:107
gtsam::StereoPoint2
Definition: StereoPoint2.h:34
gtsam::NonlinearFactor
Definition: NonlinearFactor.h:68
gtsam::StereoCamera
Definition: StereoCamera.h:47
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::OptionalMatrixType
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:55
gtsam::StereoCheiralityException
Definition: StereoCamera.h:26
T1
static const Similarity3 T1(R, Point3(3.5, -8.2, 4.2), 1)
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::GenericStereoFactor::K_
Cal3_S2Stereo::shared_ptr K_
shared pointer to calibration
Definition: StereoFactor.h:37
gtsam::GenericStereoFactor::clone
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: StereoFactor.h:98
StereoCamera.h
A Stereo Camera based on two Simple Cameras.


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:05:00