gtsam 4.1.1
gtsam
ProjectionFactor.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
21#pragma once
22
28#include <boost/optional.hpp>
29
30namespace gtsam {
31
38 template <class POSE = Pose3, class LANDMARK = Point3,
39 class CALIBRATION = Cal3_S2>
40 class GenericProjectionFactor: public NoiseModelFactor2<POSE, LANDMARK> {
41 protected:
42
43 // Keep a copy of measurement and calibration for I/O
45 boost::shared_ptr<CALIBRATION> K_;
46 boost::optional<POSE> body_P_sensor_;
47
48 // verbosity handling for Cheirality Exceptions
51
52 public:
53
56
59
61 typedef boost::shared_ptr<This> shared_ptr;
62
65 measured_(0, 0), throwCheirality_(false), verboseCheirality_(false) {
66 }
67
79 Key poseKey, Key pointKey, const boost::shared_ptr<CALIBRATION>& K,
80 boost::optional<POSE> body_P_sensor = boost::none) :
81 Base(model, poseKey, pointKey), measured_(measured), K_(K), body_P_sensor_(body_P_sensor),
82 throwCheirality_(false), verboseCheirality_(false) {}
83
97 Key poseKey, Key pointKey, const boost::shared_ptr<CALIBRATION>& K,
99 boost::optional<POSE> body_P_sensor = boost::none) :
100 Base(model, poseKey, pointKey), measured_(measured), K_(K), body_P_sensor_(body_P_sensor),
102
105
107 gtsam::NonlinearFactor::shared_ptr clone() const override {
108 return boost::static_pointer_cast<gtsam::NonlinearFactor>(
109 gtsam::NonlinearFactor::shared_ptr(new This(*this))); }
110
116 void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
117 std::cout << s << "GenericProjectionFactor, z = ";
119 if(this->body_P_sensor_)
120 this->body_P_sensor_->print(" sensor pose in body frame: ");
121 Base::print("", keyFormatter);
122 }
123
125 bool equals(const NonlinearFactor& p, double tol = 1e-9) const override {
126 const This *e = dynamic_cast<const This*>(&p);
127 return e
128 && Base::equals(p, tol)
129 && traits<Point2>::Equals(this->measured_, e->measured_, tol)
130 && this->K_->equals(*e->K_, tol)
131 && ((!body_P_sensor_ && !e->body_P_sensor_) || (body_P_sensor_ && e->body_P_sensor_ && body_P_sensor_->equals(*e->body_P_sensor_)));
132 }
133
135 Vector evaluateError(const Pose3& pose, const Point3& point,
136 boost::optional<Matrix&> H1 = boost::none, boost::optional<Matrix&> H2 = boost::none) const override {
137 try {
138 if(body_P_sensor_) {
139 if(H1) {
140 gtsam::Matrix H0;
141 PinholeCamera<CALIBRATION> camera(pose.compose(*body_P_sensor_, H0), *K_);
142 Point2 reprojectionError(camera.project(point, H1, H2, boost::none) - measured_);
143 *H1 = *H1 * H0;
144 return reprojectionError;
145 } else {
146 PinholeCamera<CALIBRATION> camera(pose.compose(*body_P_sensor_), *K_);
147 return camera.project(point, H1, H2, boost::none) - measured_;
148 }
149 } else {
150 PinholeCamera<CALIBRATION> camera(pose, *K_);
151 return camera.project(point, H1, H2, boost::none) - measured_;
152 }
153 } catch( CheiralityException& e) {
154 if (H1) *H1 = Matrix::Zero(2,6);
155 if (H2) *H2 = Matrix::Zero(2,3);
157 std::cout << e.what() << ": Landmark "<< DefaultKeyFormatter(this->key2()) <<
158 " moved behind camera " << DefaultKeyFormatter(this->key1()) << std::endl;
160 throw CheiralityException(this->key2());
161 }
162 return Vector2::Constant(2.0 * K_->fx());
163 }
164
166 const Point2& measured() const {
167 return measured_;
168 }
169
171 const boost::shared_ptr<CALIBRATION> calibration() const {
172 return K_;
173 }
174
176 const boost::optional<POSE>& body_P_sensor() const {
177 return body_P_sensor_;
178 }
179
181 inline bool verboseCheirality() const { return verboseCheirality_; }
182
184 inline bool throwCheirality() const { return throwCheirality_; }
185
186 private:
187
190 template<class ARCHIVE>
191 void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
192 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
193 ar & BOOST_SERIALIZATION_NVP(measured_);
194 ar & BOOST_SERIALIZATION_NVP(K_);
195 ar & BOOST_SERIALIZATION_NVP(body_P_sensor_);
196 ar & BOOST_SERIALIZATION_NVP(throwCheirality_);
197 ar & BOOST_SERIALIZATION_NVP(verboseCheirality_);
198 }
199
200 public:
202};
203
205 template<class POSE, class LANDMARK, class CALIBRATION>
206 struct traits<GenericProjectionFactor<POSE, LANDMARK, CALIBRATION> > :
207 public Testable<GenericProjectionFactor<POSE, LANDMARK, CALIBRATION> > {
208 };
209
210} // \ namespace gtsam
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
This marks a GTSAM object to require alignment.
Definition: types.h:277
The most common 5DOF 3D->2D calibration.
3D Point
Base class for all pinhole cameras.
3D Pose
Non-linear factor base classes.
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
Vector2 Point2
As of GTSAM 4, in order to make GTSAM more lean, it is now possible to just typedef Point2 to Vector2...
Definition: Point2.h:27
Vector3 Point3
As of GTSAM 4, in order to make GTSAM more lean, it is now possible to just typedef Point3 to Vector3...
Definition: Point3.h:35
noiseModel::Base::shared_ptr SharedNoiseModel
Note, deliberately not in noiseModel namespace.
Definition: NoiseModel.h:736
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:69
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
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
A helper that implements the traits interface for GTSAM types.
Definition: Testable.h:151
Definition: CalibratedCamera.h:32
Definition: PinholeCamera.h:33
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none, OptionalJacobian< 2, DimK > Dcal=boost::none) const
project a 3D point from world coordinates into the image
Definition: PinholePose.h:118
Definition: Pose3.h:37
This is the base class for all factor types.
Definition: Factor.h:56
Nonlinear factor base class.
Definition: NonlinearFactor.h:43
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
Check if two factors are equal.
Definition: NonlinearFactor.cpp:71
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Print.
Definition: NonlinearFactor.cpp:63
A convenient base class for creating your own NoiseModelFactor with 2 variables.
Definition: NonlinearFactor.h:369
Key key1() const
methods to retrieve both keys
Definition: NonlinearFactor.h:401
Definition: ProjectionFactor.h:40
bool verboseCheirality() const
return verbosity
Definition: ProjectionFactor.h:181
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Definition: ProjectionFactor.h:116
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Definition: ProjectionFactor.h:125
Point2 measured_
2D measurement
Definition: ProjectionFactor.h:44
GenericProjectionFactor< POSE, LANDMARK, CALIBRATION > This
shorthand for this class
Definition: ProjectionFactor.h:58
const Point2 & measured() const
return the measurement
Definition: ProjectionFactor.h:166
boost::optional< POSE > body_P_sensor_
The pose of the sensor in the body frame.
Definition: ProjectionFactor.h:46
boost::shared_ptr< CALIBRATION > K_
shared pointer to calibration object
Definition: ProjectionFactor.h:45
~GenericProjectionFactor() override
Virtual destructor.
Definition: ProjectionFactor.h:104
Vector evaluateError(const Pose3 &pose, const Point3 &point, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
Evaluate error h(x)-z and optionally derivatives.
Definition: ProjectionFactor.h:135
GenericProjectionFactor()
Default constructor.
Definition: ProjectionFactor.h:64
bool throwCheirality_
If true, rethrows Cheirality exceptions (default: false)
Definition: ProjectionFactor.h:49
const boost::optional< POSE > & body_P_sensor() const
return the (optional) sensor pose with respect to the vehicle frame
Definition: ProjectionFactor.h:176
bool throwCheirality() const
return flag for throwing cheirality exceptions
Definition: ProjectionFactor.h:184
GenericProjectionFactor(const Point2 &measured, const SharedNoiseModel &model, Key poseKey, Key pointKey, const boost::shared_ptr< CALIBRATION > &K, bool throwCheirality, bool verboseCheirality, boost::optional< POSE > body_P_sensor=boost::none)
Constructor with exception-handling flags TODO: Mark argument order standard (keys,...
Definition: ProjectionFactor.h:96
friend class boost::serialization::access
Serialization function.
Definition: ProjectionFactor.h:189
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: ProjectionFactor.h:107
boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Definition: ProjectionFactor.h:61
bool verboseCheirality_
If true, prints text for Cheirality exceptions (default: false)
Definition: ProjectionFactor.h:50
GenericProjectionFactor(const Point2 &measured, const SharedNoiseModel &model, Key poseKey, Key pointKey, const boost::shared_ptr< CALIBRATION > &K, boost::optional< POSE > body_P_sensor=boost::none)
Constructor TODO: Mark argument order standard (keys, measurement, parameters)
Definition: ProjectionFactor.h:78
const boost::shared_ptr< CALIBRATION > calibration() const
return the calibration object
Definition: ProjectionFactor.h:171
NoiseModelFactor2< POSE, LANDMARK > Base
shorthand for base class type
Definition: ProjectionFactor.h:55