30 Cal3_S2::shared_ptr
K_;
35 typedef NoiseModelFactor2<Pose3, Vector3>
Base;
38 using Base::evaluateError;
48 measured_(0.0, 0.0), K_(new
Cal3_S2(444, 555, 666, 777, 888)) {
63 Base(model, poseKey, landmarkKey), measured_(measured), K_(K) {}
73 void print(
const std::string& s =
"InvDepthFactorVariant3a",
74 const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const override {
81 const This *e =
dynamic_cast<const This*
>(&p);
83 && Base::equals(p, tol)
85 && this->K_->equals(*e->K_, tol);
88 Vector inverseDepthError(
const Pose3& pose,
const Vector3& landmark)
const {
91 double theta = landmark(0), phi = landmark(1), rho = landmark(2);
92 Point3 pose_P_landmark(cos(phi)*sin(theta)/rho, sin(phi)/rho, cos(phi)*cos(theta)/rho);
100 <<
": Inverse Depth Landmark [" << DefaultKeyFormatter(this->key<1>()) <<
"," << DefaultKeyFormatter(this->key<2>()) <<
"]" 101 <<
" moved behind camera [" << DefaultKeyFormatter(this->key<1>()) <<
"]" 103 return Vector::Ones(2) * 2.0 * K_->fx();
105 return (Vector(1) << 0.0).finished();
113 (*H1) = numericalDerivative11<Vector, Pose3>(
114 std::bind(&InvDepthFactorVariant3a::inverseDepthError,
this,
115 std::placeholders::_1, landmark),
119 (*H2) = numericalDerivative11<Vector, Vector3>(
120 std::bind(&InvDepthFactorVariant3a::inverseDepthError,
this, pose,
121 std::placeholders::_1),
125 return inverseDepthError(pose, landmark);
140 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 141 friend class boost::serialization::access; 143 template<
class ARCHIVE>
144 void serialize(ARCHIVE & ar,
const unsigned int ) {
145 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
146 ar & BOOST_SERIALIZATION_NVP(measured_);
147 ar & BOOST_SERIALIZATION_NVP(K_);
160 Cal3_S2::shared_ptr
K_;
175 measured_(0.0, 0.0), K_(new
Cal3_S2(444, 555, 666, 777, 888)) {
190 Base(model, poseKey1, poseKey2, landmarkKey), measured_(measured), K_(K) {}
200 void print(
const std::string& s =
"InvDepthFactorVariant3",
201 const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const override {
208 const This *e =
dynamic_cast<const This*
>(&p);
210 && Base::equals(p, tol)
212 && this->K_->equals(*e->K_, tol);
215 Vector inverseDepthError(
const Pose3& pose1,
const Pose3& pose2,
const Vector3& landmark)
const {
218 double theta = landmark(0), phi = landmark(1), rho = landmark(2);
219 Point3 pose1_P_landmark(cos(phi)*sin(theta)/rho, sin(phi)/rho, cos(phi)*cos(theta)/rho);
226 std::cout << e.what()
227 <<
": Inverse Depth Landmark [" << DefaultKeyFormatter(this->key<1>()) <<
"," << DefaultKeyFormatter(this->key<3>()) <<
"]" 228 <<
" moved behind camera " << DefaultKeyFormatter(this->key<2>())
230 return Vector::Ones(2) * 2.0 * K_->fx();
232 return (Vector(1) << 0.0).finished();
240 (*H1) = numericalDerivative11<Vector, Pose3>(
241 std::bind(&InvDepthFactorVariant3b::inverseDepthError,
this,
242 std::placeholders::_1, pose2, landmark),
246 (*H2) = numericalDerivative11<Vector, Pose3>(
247 std::bind(&InvDepthFactorVariant3b::inverseDepthError,
this, pose1,
248 std::placeholders::_1, landmark),
252 (*H3) = numericalDerivative11<Vector, Vector3>(
253 std::bind(&InvDepthFactorVariant3b::inverseDepthError,
this, pose1,
254 pose2, std::placeholders::_1),
257 return inverseDepthError(pose1, pose2, landmark);
272 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 273 friend class boost::serialization::access;
275 template<
class ARCHIVE>
276 void serialize(ARCHIVE & ar,
const unsigned int ) {
277 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
278 ar & BOOST_SERIALIZATION_NVP(measured_);
279 ar & BOOST_SERIALIZATION_NVP(K_);
InvDepthFactorVariant3b This
shorthand for this class
Definition: InvDepthFactorVariant3.h:168
Definition: NonlinearFactor.h:431
const Point2 & imagePoint() const
Definition: InvDepthFactorVariant3.h:129
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:113
InvDepthFactorVariant3a This
shorthand for this class
Definition: InvDepthFactorVariant3.h:41
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Definition: InvDepthFactorVariant3.h:207
NoiseModelFactorN< Pose3, Pose3, Vector3 > Base
shorthand for base class type
Definition: InvDepthFactorVariant3.h:165
Vector2 Point2
Definition: Point2.h:32
Definition: NonlinearFactor.h:68
void print(const std::string &s="InvDepthFactorVariant3a", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: InvDepthFactorVariant3.h:73
InvDepthFactorVariant3a()
Default constructor.
Definition: InvDepthFactorVariant3.h:47
Some functions to compute numerical derivatives.
InvDepthFactorVariant3a(const Key poseKey, const Key landmarkKey, const Point2 &measured, const Cal3_S2::shared_ptr &K, const SharedNoiseModel &model)
Definition: InvDepthFactorVariant3.h:61
Vector evaluateError(const Pose3 &pose, const Vector3 &landmark, OptionalMatrixType H1, OptionalMatrixType H2) const override
Evaluate error h(x)-z and optionally derivatives.
Definition: InvDepthFactorVariant3.h:109
const Cal3_S2::shared_ptr calibration() const
Definition: InvDepthFactorVariant3.h:134
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Definition: InvDepthFactorVariant3.h:80
Point3 transformFrom(const Point3 &point, OptionalJacobian< 3, 6 > Hself={}, OptionalJacobian< 3, 3 > Hpoint={}) const
takes point in Pose coordinates and transforms it to world coordinates
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Definition: InvDepthFactorVariant3.h:171
Base class for all pinhole cameras.
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const
project a 3D point from world coordinates into the image
Definition: PinholePose.h:112
~InvDepthFactorVariant3b() override
Definition: InvDepthFactorVariant3.h:193
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:55
InvDepthFactorVariant3b()
Default constructor.
Definition: InvDepthFactorVariant3.h:174
GTSAM_EXPORT void print(const Matrix &A, const std::string &s, std::ostream &stream)
The most common 5DOF 3D->2D calibration.
Definition: Cal3_S2.h:34
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
Definition: InvDepthFactorVariant3.h:25
Definition: PinholeCamera.h:33
Definition: chartTesting.h:28
Point2 measured_
2D measurement
Definition: InvDepthFactorVariant3.h:29
Non-linear factor base classes.
Point2 measured_
2D measurement
Definition: InvDepthFactorVariant3.h:159
const Cal3_S2::shared_ptr calibration() const
Definition: InvDepthFactorVariant3.h:266
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Definition: InvDepthFactorVariant3.h:44
const Point2 & imagePoint() const
Definition: InvDepthFactorVariant3.h:261
Vector evaluateError(const Pose3 &pose1, const Pose3 &pose2, const Vector3 &landmark, OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3) const override
Evaluate error h(x)-z and optionally derivatives.
Definition: InvDepthFactorVariant3.h:236
Definition: CalibratedCamera.h:34
Definition: InvDepthFactorVariant3.h:155
Cal3_S2::shared_ptr K_
shared pointer to calibration object
Definition: InvDepthFactorVariant3.h:160
Vector3 Point3
Definition: Point3.h:38
NoiseModelFactor2< Pose3, Vector3 > Base
shorthand for base class type
Definition: InvDepthFactorVariant3.h:35
~InvDepthFactorVariant3a() override
Definition: InvDepthFactorVariant3.h:66
void print(const std::string &s="InvDepthFactorVariant3", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: InvDepthFactorVariant3.h:200
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
InvDepthFactorVariant3b(const Key poseKey1, const Key poseKey2, const Key landmarkKey, const Point2 &measured, const Cal3_S2::shared_ptr &K, const SharedNoiseModel &model)
Definition: InvDepthFactorVariant3.h:188
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
The most common 5DOF 3D->2D calibration.
Cal3_S2::shared_ptr K_
shared pointer to calibration object
Definition: InvDepthFactorVariant3.h:30