gtsam 4.1.1
gtsam
InvDepthFactorVariant3.h
Go to the documentation of this file.
1
11#pragma once
12
19
20#include <boost/bind/bind.hpp>
21
22namespace gtsam {
23
27class InvDepthFactorVariant3a: public NoiseModelFactor2<Pose3, Vector3> {
28protected:
29
30 // Keep a copy of measurement and calibration for I/O
32 Cal3_S2::shared_ptr K_;
33
34public:
35
38
41
43 typedef boost::shared_ptr<This> shared_ptr;
44
47 measured_(0.0, 0.0), K_(new Cal3_S2(444, 555, 666, 777, 888)) {
48 }
49
60 InvDepthFactorVariant3a(const Key poseKey, const Key landmarkKey,
61 const Point2& measured, const Cal3_S2::shared_ptr& K, const SharedNoiseModel& model) :
62 Base(model, poseKey, landmarkKey), measured_(measured), K_(K) {}
63
66
72 void print(const std::string& s = "InvDepthFactorVariant3a",
73 const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
74 Base::print(s, keyFormatter);
76 }
77
79 bool equals(const NonlinearFactor& p, double tol = 1e-9) const override {
80 const This *e = dynamic_cast<const This*>(&p);
81 return e
82 && Base::equals(p, tol)
83 && traits<Point2>::Equals(this->measured_, e->measured_, tol)
84 && this->K_->equals(*e->K_, tol);
85 }
86
87 Vector inverseDepthError(const Pose3& pose, const Vector3& landmark) const {
88 try {
89 // Calculate the 3D coordinates of the landmark in the Pose frame
90 double theta = landmark(0), phi = landmark(1), rho = landmark(2);
91 Point3 pose_P_landmark(cos(phi)*sin(theta)/rho, sin(phi)/rho, cos(phi)*cos(theta)/rho);
92 // Convert the landmark to world coordinates
93 Point3 world_P_landmark = pose.transformFrom(pose_P_landmark);
94 // Project landmark into Pose2
95 PinholeCamera<Cal3_S2> camera(pose, *K_);
96 return camera.project(world_P_landmark) - measured_;
97 } catch( CheiralityException& e) {
98 std::cout << e.what()
99 << ": Inverse Depth Landmark [" << DefaultKeyFormatter(this->key1()) << "," << DefaultKeyFormatter(this->key2()) << "]"
100 << " moved behind camera [" << DefaultKeyFormatter(this->key1()) << "]"
101 << std::endl;
102 return Vector::Ones(2) * 2.0 * K_->fx();
103 }
104 return (Vector(1) << 0.0).finished();
105 }
106
108 Vector evaluateError(const Pose3& pose, const Vector3& landmark,
109 boost::optional<Matrix&> H1=boost::none,
110 boost::optional<Matrix&> H2=boost::none) const override {
111
112 if(H1) {
113 (*H1) = numericalDerivative11<Vector, Pose3>(
114 std::bind(&InvDepthFactorVariant3a::inverseDepthError, this,
115 std::placeholders::_1, landmark),
116 pose);
117 }
118 if(H2) {
119 (*H2) = numericalDerivative11<Vector, Vector3>(
120 std::bind(&InvDepthFactorVariant3a::inverseDepthError, this, pose,
121 std::placeholders::_1),
122 landmark);
123 }
124
125 return inverseDepthError(pose, landmark);
126 }
127
129 const Point2& imagePoint() const {
130 return measured_;
131 }
132
134 const Cal3_S2::shared_ptr calibration() const {
135 return K_;
136 }
137
138private:
139
142 template<class ARCHIVE>
143 void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
144 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
145 ar & BOOST_SERIALIZATION_NVP(measured_);
146 ar & BOOST_SERIALIZATION_NVP(K_);
147 }
148};
149
153class InvDepthFactorVariant3b: public NoiseModelFactor3<Pose3, Pose3, Vector3> {
154protected:
155
156 // Keep a copy of measurement and calibration for I/O
158 Cal3_S2::shared_ptr K_;
159
160public:
161
164
167
169 typedef boost::shared_ptr<This> shared_ptr;
170
173 measured_(0.0, 0.0), K_(new Cal3_S2(444, 555, 666, 777, 888)) {
174 }
175
186 InvDepthFactorVariant3b(const Key poseKey1, const Key poseKey2, const Key landmarkKey,
187 const Point2& measured, const Cal3_S2::shared_ptr& K, const SharedNoiseModel& model) :
188 Base(model, poseKey1, poseKey2, landmarkKey), measured_(measured), K_(K) {}
189
192
198 void print(const std::string& s = "InvDepthFactorVariant3",
199 const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override {
200 Base::print(s, keyFormatter);
202 }
203
205 bool equals(const NonlinearFactor& p, double tol = 1e-9) const override {
206 const This *e = dynamic_cast<const This*>(&p);
207 return e
208 && Base::equals(p, tol)
209 && traits<Point2>::Equals(this->measured_, e->measured_, tol)
210 && this->K_->equals(*e->K_, tol);
211 }
212
213 Vector inverseDepthError(const Pose3& pose1, const Pose3& pose2, const Vector3& landmark) const {
214 try {
215 // Calculate the 3D coordinates of the landmark in the Pose1 frame
216 double theta = landmark(0), phi = landmark(1), rho = landmark(2);
217 Point3 pose1_P_landmark(cos(phi)*sin(theta)/rho, sin(phi)/rho, cos(phi)*cos(theta)/rho);
218 // Convert the landmark to world coordinates
219 Point3 world_P_landmark = pose1.transformFrom(pose1_P_landmark);
220 // Project landmark into Pose2
221 PinholeCamera<Cal3_S2> camera(pose2, *K_);
222 return camera.project(world_P_landmark) - measured_;
223 } catch( CheiralityException& e) {
224 std::cout << e.what()
225 << ": Inverse Depth Landmark [" << DefaultKeyFormatter(this->key1()) << "," << DefaultKeyFormatter(this->key3()) << "]"
226 << " moved behind camera " << DefaultKeyFormatter(this->key2())
227 << std::endl;
228 return Vector::Ones(2) * 2.0 * K_->fx();
229 }
230 return (Vector(1) << 0.0).finished();
231 }
232
234 Vector evaluateError(const Pose3& pose1, const Pose3& pose2, const Vector3& landmark,
235 boost::optional<Matrix&> H1=boost::none,
236 boost::optional<Matrix&> H2=boost::none,
237 boost::optional<Matrix&> H3=boost::none) const override {
238
239 if(H1)
240 (*H1) = numericalDerivative11<Vector, Pose3>(
241 std::bind(&InvDepthFactorVariant3b::inverseDepthError, this,
242 std::placeholders::_1, pose2, landmark),
243 pose1);
244
245 if(H2)
246 (*H2) = numericalDerivative11<Vector, Pose3>(
247 std::bind(&InvDepthFactorVariant3b::inverseDepthError, this, pose1,
248 std::placeholders::_1, landmark),
249 pose2);
250
251 if(H3)
252 (*H3) = numericalDerivative11<Vector, Vector3>(
253 std::bind(&InvDepthFactorVariant3b::inverseDepthError, this, pose1,
254 pose2, std::placeholders::_1),
255 landmark);
256
257 return inverseDepthError(pose1, pose2, landmark);
258 }
259
261 const Point2& imagePoint() const {
262 return measured_;
263 }
264
266 const Cal3_S2::shared_ptr calibration() const {
267 return K_;
268 }
269
270private:
271
274 template<class ARCHIVE>
275 void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
276 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
277 ar & BOOST_SERIALIZATION_NVP(measured_);
278 ar & BOOST_SERIALIZATION_NVP(K_);
279 }
280};
281
282} // \ namespace gtsam
Some functions to compute numerical derivatives.
The most common 5DOF 3D->2D calibration.
Base class for all pinhole cameras.
3D Pose
2D Point
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
Definition: Cal3_S2.h:34
Definition: PinholeCamera.h:33
Definition: Pose3.h:37
Point3 transformFrom(const Point3 &point, OptionalJacobian< 3, 6 > Hself=boost::none, OptionalJacobian< 3, 3 > Hpoint=boost::none) const
takes point in Pose coordinates and transforms it to world coordinates
Definition: Pose3.cpp:342
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
A convenient base class for creating your own NoiseModelFactor with 3 variables.
Definition: NonlinearFactor.h:444
Key key1() const
methods to retrieve keys
Definition: NonlinearFactor.h:478
Binary factor representing the first visual measurement using an inverse-depth parameterization.
Definition: InvDepthFactorVariant3.h:27
Cal3_S2::shared_ptr K_
shared pointer to calibration object
Definition: InvDepthFactorVariant3.h:32
const Point2 & imagePoint() const
return the measurement
Definition: InvDepthFactorVariant3.h:129
boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Definition: InvDepthFactorVariant3.h:43
InvDepthFactorVariant3a()
Default constructor.
Definition: InvDepthFactorVariant3.h:46
void print(const std::string &s="InvDepthFactorVariant3a", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Definition: InvDepthFactorVariant3.h:72
~InvDepthFactorVariant3a() override
Virtual destructor.
Definition: InvDepthFactorVariant3.h:65
NoiseModelFactor2< Pose3, Vector3 > Base
shorthand for base class type
Definition: InvDepthFactorVariant3.h:37
Point2 measured_
2D measurement
Definition: InvDepthFactorVariant3.h:31
Vector evaluateError(const Pose3 &pose, const Vector3 &landmark, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
Evaluate error h(x)-z and optionally derivatives.
Definition: InvDepthFactorVariant3.h:108
const Cal3_S2::shared_ptr calibration() const
return the calibration object
Definition: InvDepthFactorVariant3.h:134
friend class boost::serialization::access
Serialization function.
Definition: InvDepthFactorVariant3.h:141
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Definition: InvDepthFactorVariant3.h:79
InvDepthFactorVariant3a This
shorthand for this class
Definition: InvDepthFactorVariant3.h:40
InvDepthFactorVariant3a(const Key poseKey, const Key landmarkKey, const Point2 &measured, const Cal3_S2::shared_ptr &K, const SharedNoiseModel &model)
Constructor TODO: Mark argument order standard (keys, measurement, parameters)
Definition: InvDepthFactorVariant3.h:60
Ternary factor representing a visual measurement using an inverse-depth parameterization.
Definition: InvDepthFactorVariant3.h:153
void print(const std::string &s="InvDepthFactorVariant3", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Definition: InvDepthFactorVariant3.h:198
Vector evaluateError(const Pose3 &pose1, const Pose3 &pose2, const Vector3 &landmark, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none, boost::optional< Matrix & > H3=boost::none) const override
Evaluate error h(x)-z and optionally derivatives.
Definition: InvDepthFactorVariant3.h:234
const Point2 & imagePoint() const
return the measurement
Definition: InvDepthFactorVariant3.h:261
InvDepthFactorVariant3b(const Key poseKey1, const Key poseKey2, const Key landmarkKey, const Point2 &measured, const Cal3_S2::shared_ptr &K, const SharedNoiseModel &model)
Constructor TODO: Mark argument order standard (keys, measurement, parameters)
Definition: InvDepthFactorVariant3.h:186
NoiseModelFactor3< Pose3, Pose3, Vector3 > Base
shorthand for base class type
Definition: InvDepthFactorVariant3.h:163
Cal3_S2::shared_ptr K_
shared pointer to calibration object
Definition: InvDepthFactorVariant3.h:158
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Definition: InvDepthFactorVariant3.h:205
~InvDepthFactorVariant3b() override
Virtual destructor.
Definition: InvDepthFactorVariant3.h:191
InvDepthFactorVariant3b This
shorthand for this class
Definition: InvDepthFactorVariant3.h:166
friend class boost::serialization::access
Serialization function.
Definition: InvDepthFactorVariant3.h:273
InvDepthFactorVariant3b()
Default constructor.
Definition: InvDepthFactorVariant3.h:172
Point2 measured_
2D measurement
Definition: InvDepthFactorVariant3.h:157
boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Definition: InvDepthFactorVariant3.h:169
const Cal3_S2::shared_ptr calibration() const
return the calibration object
Definition: InvDepthFactorVariant3.h:266