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",
81 const This *
e =
dynamic_cast<const This*
>(&
p);
83 && Base::equals(p,
tol)
85 && this->K_->equals(*e->K_,
tol);
103 return Vector::Ones(2) * 2.0 * K_->fx();
105 return (
Vector(1) << 0.0).finished();
113 (*H1) = numericalDerivative11<Vector, Pose3>(
115 std::placeholders::_1, landmark),
119 (*H2) = numericalDerivative11<Vector, Vector3>(
121 std::placeholders::_1),
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_);
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",
208 const This *
e =
dynamic_cast<const This*
>(&
p);
210 && Base::equals(p,
tol)
212 && this->K_->equals(*e->K_,
tol);
226 std::cout << e.
what()
230 return Vector::Ones(2) * 2.0 * K_->fx();
232 return (
Vector(1) << 0.0).finished();
240 (*H1) = numericalDerivative11<Vector, Pose3>(
242 std::placeholders::_1, pose2, landmark),
246 (*H2) = numericalDerivative11<Vector, Pose3>(
248 std::placeholders::_1, landmark),
252 (*H3) = numericalDerivative11<Vector, Vector3>(
254 pose2, std::placeholders::_1),
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
Vector inverseDepthError(const Pose3 &pose1, const Pose3 &pose2, const Vector3 &landmark) const
Jet< T, N > cos(const Jet< T, N > &f)
const Point2 & imagePoint() const
std::string serialize(const T &input)
serializes to a string
noiseModel::Diagonal::shared_ptr model
InvDepthFactorVariant3a This
shorthand for this class
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
NoiseModelFactorN< Pose3, Pose3, Vector3 > Base
shorthand for base class type
Jet< T, N > sin(const Jet< T, N > &f)
void print(const std::string &s="InvDepthFactorVariant3a", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
InvDepthFactorVariant3a()
Default constructor.
Some functions to compute numerical derivatives.
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
InvDepthFactorVariant3a(const Key poseKey, const Key landmarkKey, const Point2 &measured, const Cal3_S2::shared_ptr &K, const SharedNoiseModel &model)
Vector evaluateError(const Pose3 &pose, const Vector3 &landmark, OptionalMatrixType H1, OptionalMatrixType H2) const override
Evaluate error h(x)-z and optionally derivatives.
const Cal3_S2::shared_ptr calibration() const
static const KeyFormatter DefaultKeyFormatter
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
static Point3 landmark(0, 0, 5)
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
~InvDepthFactorVariant3b() override
Matrix * OptionalMatrixType
std::shared_ptr< Cal3_S2 > shared_ptr
InvDepthFactorVariant3b()
Default constructor.
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
Array< double, 1, 3 > e(1./3., 0.5, 2.)
The most common 5DOF 3D->2D calibration.
Vector inverseDepthError(const Pose3 &pose, const Vector3 &landmark) const
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
static Key poseKey1(X(1))
Point2 measured_
2D measurement
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Non-linear factor base classes.
Point2 measured_
2D measurement
const Cal3_S2::shared_ptr calibration() const
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
const Point2 & imagePoint() const
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.
Cal3_S2::shared_ptr K_
shared pointer to calibration object
static Key poseKey2(X(2))
NoiseModelFactor2< Pose3, Vector3 > Base
shorthand for base class type
static const CalibratedCamera camera(kDefaultPose)
~InvDepthFactorVariant3a() override
void print(const std::string &s="InvDepthFactorVariant3", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
std::uint64_t Key
Integer nonlinear key type.
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
InvDepthFactorVariant3b(const Key poseKey1, const Key poseKey2, const Key landmarkKey, const Point2 &measured, const Cal3_S2::shared_ptr &K, const SharedNoiseModel &model)
noiseModel::Base::shared_ptr SharedNoiseModel
The most common 5DOF 3D->2D calibration.
const char * what() const noexcept override
Cal3_S2::shared_ptr K_
shared pointer to calibration object