20#include <boost/bind/bind.hpp>
32 Cal3_S2::shared_ptr
K_;
70 void print(
const std::string& s =
"InvDepthFactorVariant1",
71 const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const override {
78 const This *e =
dynamic_cast<const This*
>(&p);
82 && this->K_->equals(*e->
K_, tol);
85 Vector inverseDepthError(
const Pose3& pose,
const Vector6& landmark)
const {
88 double x = landmark(0), y = landmark(1), z = landmark(2);
89 double theta = landmark(3), phi = landmark(4), rho = landmark(5);
90 Point3 world_P_landmark =
Point3(x, y, z) +
Point3(cos(theta)*cos(phi)/rho, sin(theta)*cos(phi)/rho, sin(phi)/rho);
93 return camera.project(world_P_landmark) -
measured_;
94 }
catch( CheiralityException& e) {
96 <<
": Inverse Depth Landmark [" << DefaultKeyFormatter(this->
key<2>()) <<
"]"
97 <<
" moved behind camera [" << DefaultKeyFormatter(this->
key<1>()) <<
"]"
99 return Vector::Ones(2) * 2.0 *
K_->fx();
101 return (Vector(1) << 0.0).finished();
106 boost::optional<Matrix&> H1=boost::none,
107 boost::optional<Matrix&> H2=boost::none)
const override {
111 std::bind(&InvDepthFactorVariant1::inverseDepthError,
this,
112 std::placeholders::_1, landmark),
117 std::bind(&InvDepthFactorVariant1::inverseDepthError,
this, pose,
118 std::placeholders::_1), landmark);
121 return inverseDepthError(pose, landmark);
138 template<
class ARCHIVE>
139 void serialize(ARCHIVE & ar,
const unsigned int ) {
140 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
142 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
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
~InvDepthFactorVariant1() override
Virtual destructor.
Definition InvDepthFactorVariant1.h:63
const Point2 & imagePoint() const
return the measurement
Definition InvDepthFactorVariant1.h:125
InvDepthFactorVariant1(const Key poseKey, const Key landmarkKey, const Point2 &measured, const Cal3_S2::shared_ptr &K, const SharedNoiseModel &model)
Constructor.
Definition InvDepthFactorVariant1.h:58
NoiseModelFactorN< Pose3, Vector6 > Base
shorthand for base class type
Definition InvDepthFactorVariant1.h:37
void print(const std::string &s="InvDepthFactorVariant1", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
print
Definition InvDepthFactorVariant1.h:70
InvDepthFactorVariant1()
Default constructor.
Definition InvDepthFactorVariant1.h:46
InvDepthFactorVariant1 This
shorthand for this class
Definition InvDepthFactorVariant1.h:40
const Cal3_S2::shared_ptr calibration() const
return the calibration object
Definition InvDepthFactorVariant1.h:130
Cal3_S2::shared_ptr K_
shared pointer to calibration object
Definition InvDepthFactorVariant1.h:32
Point2 measured_
2D measurement
Definition InvDepthFactorVariant1.h:31
friend class boost::serialization::access
Serialization function.
Definition InvDepthFactorVariant1.h:137
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Definition InvDepthFactorVariant1.h:77
Vector evaluateError(const Pose3 &pose, const Vector6 &landmark, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
Evaluate error h(x)-z and optionally derivatives.
Definition InvDepthFactorVariant1.h:105
boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Definition InvDepthFactorVariant1.h:43