20#include <boost/bind/bind.hpp>
32 Cal3_S2::shared_ptr
K_;
72 void print(
const std::string& s =
"InvDepthFactorVariant3a",
73 const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const override {
80 const This *e =
dynamic_cast<const This*
>(&p);
84 && this->K_->equals(*e->
K_, tol);
87 Vector inverseDepthError(
const Pose3& pose,
const Vector3& landmark)
const {
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);
96 return camera.project(world_P_landmark) -
measured_;
97 }
catch( CheiralityException& e) {
99 <<
": Inverse Depth Landmark [" << DefaultKeyFormatter(this->
key<1>()) <<
"," << DefaultKeyFormatter(this->
key<2>()) <<
"]"
100 <<
" moved behind camera [" << DefaultKeyFormatter(this->
key<1>()) <<
"]"
102 return Vector::Ones(2) * 2.0 *
K_->fx();
104 return (Vector(1) << 0.0).finished();
109 boost::optional<Matrix&> H1=boost::none,
110 boost::optional<Matrix&> H2=boost::none)
const override {
114 std::bind(&InvDepthFactorVariant3a::inverseDepthError,
this,
115 std::placeholders::_1, landmark),
120 std::bind(&InvDepthFactorVariant3a::inverseDepthError,
this, pose,
121 std::placeholders::_1),
125 return inverseDepthError(pose, landmark);
142 template<
class ARCHIVE>
143 void serialize(ARCHIVE & ar,
const unsigned int ) {
144 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
146 ar & BOOST_SERIALIZATION_NVP(
K_);
158 Cal3_S2::shared_ptr
K_;
188 Base(model, poseKey1, poseKey2, landmarkKey),
measured_(measured),
K_(K) {}
198 void print(
const std::string& s =
"InvDepthFactorVariant3",
199 const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const override {
206 const This *e =
dynamic_cast<const This*
>(&p);
210 && this->K_->equals(*e->
K_, tol);
213 Vector inverseDepthError(
const Pose3& pose1,
const Pose3& pose2,
const Vector3& landmark)
const {
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);
222 return camera.project(world_P_landmark) -
measured_;
223 }
catch( CheiralityException& e) {
224 std::cout << e.what()
225 <<
": Inverse Depth Landmark [" << DefaultKeyFormatter(this->
key<1>()) <<
"," << DefaultKeyFormatter(this->
key<3>()) <<
"]"
226 <<
" moved behind camera " << DefaultKeyFormatter(this->
key<2>())
228 return Vector::Ones(2) * 2.0 *
K_->fx();
230 return (Vector(1) << 0.0).finished();
235 boost::optional<Matrix&> H1=boost::none,
236 boost::optional<Matrix&> H2=boost::none,
237 boost::optional<Matrix&> H3=boost::none)
const override {
241 std::bind(&InvDepthFactorVariant3b::inverseDepthError,
this,
242 std::placeholders::_1, pose2, landmark),
247 std::bind(&InvDepthFactorVariant3b::inverseDepthError,
this, pose1,
248 std::placeholders::_1, landmark),
253 std::bind(&InvDepthFactorVariant3b::inverseDepthError,
this, pose1,
254 pose2, std::placeholders::_1),
257 return inverseDepthError(pose1, pose2, landmark);
274 template<
class ARCHIVE>
275 void serialize(ARCHIVE & ar,
const unsigned int ) {
276 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
278 ar & BOOST_SERIALIZATION_NVP(
K_);
Some functions to compute numerical derivatives.
The most common 5DOF 3D->2D calibration.
Base class for all pinhole cameras.
Non-linear factor base classes.
Global functions in a separate testing namespace.
Definition chartTesting.h:28
internal::FixedSizeMatrix< Y, X >::type numericalDerivative11(std::function< Y(const X &)> h, const X &x, double delta=1e-5)
New-style numerical derivatives using manifold_traits.
Definition numericalDerivative.h:110
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
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
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:36
noiseModel::Base::shared_ptr SharedNoiseModel
Aliases.
Definition NoiseModel.h:724
std::uint64_t Key
Integer nonlinear key type.
Definition types.h:100
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition concepts.h:30
The most common 5DOF 3D->2D calibration.
Definition Cal3_S2.h:34
A pinhole camera class that has a Pose3 and a Calibration.
Definition PinholeCamera.h:33
A 3D pose (R,t) : (Rot3,Point3).
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:347
virtual void print(const std::string &s="Factor", const KeyFormatter &formatter=DefaultKeyFormatter) const
print
Definition Factor.cpp:29
bool equals(const This &other, double tol=1e-9) const
check equality
Definition Factor.cpp:42
Nonlinear factor base class.
Definition NonlinearFactor.h:42
NoiseModelFactorN()
Definition NonlinearFactor.h:469
Key key() const
Definition NonlinearFactor.h:518
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
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
NoiseModelFactorN< Pose3, Vector3 > Base
shorthand for base class type
Definition InvDepthFactorVariant3.h:37
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
NoiseModelFactorN< Pose3, Pose3, Vector3 > Base
shorthand for base class type
Definition InvDepthFactorVariant3.h:163
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
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