Go to the documentation of this file.
35 typedef NoiseModelFactor2<Pose3, Vector3>
Base;
38 using Base::evaluateError;
73 void print(
const std::string&
s =
"InvDepthFactorVariant3a",
83 && Base::equals(
p,
tol)
85 && this->K_->equals(*
e->K_,
tol);
94 Point3 world_P_landmark =
pose.transformFrom(pose_P_landmark);
103 return Vector::Ones(2) * 2.0 *
K_->fx();
105 return (
Vector(1) << 0.0).finished();
113 (*H1) = numericalDerivative11<Vector, Pose3>(
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);
147 ar & BOOST_SERIALIZATION_NVP(
K_);
200 void print(
const std::string&
s =
"InvDepthFactorVariant3",
208 const This *
e =
dynamic_cast<const This*
>(&
p);
212 && this->K_->equals(*
e->K_,
tol);
221 Point3 world_P_landmark =
pose1.transformFrom(pose1_P_landmark);
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>(
246 (*H2) = numericalDerivative11<Vector, Pose3>(
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);
279 ar & BOOST_SERIALIZATION_NVP(
K_);
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
InvDepthFactorVariant3b(const Key poseKey1, const Key poseKey2, const Key landmarkKey, const Point2 &measured, const Cal3_S2::shared_ptr &K, const SharedNoiseModel &model)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
void print(const std::string &s="InvDepthFactorVariant3", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Jet< T, N > sin(const Jet< T, N > &f)
The most common 5DOF 3D->2D calibration.
InvDepthFactorVariant3a(const Key poseKey, const Key landmarkKey, const Point2 &measured, const Cal3_S2::shared_ptr &K, const SharedNoiseModel &model)
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
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.
Jet< T, N > cos(const Jet< T, N > &f)
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Some functions to compute numerical derivatives.
const Point2 & imagePoint() const
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
static Point3 landmark(0, 0, 5)
Base class for all pinhole cameras.
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
noiseModel::Base::shared_ptr SharedNoiseModel
std::shared_ptr< Cal3_S2 > shared_ptr
const Cal3_S2::shared_ptr calibration() const
Vector inverseDepthError(const Pose3 &pose1, const Pose3 &pose2, const Vector3 &landmark) const
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
NoiseModelFactorN< Pose3, Pose3, Vector3 > Base
shorthand for base class type
noiseModel::Diagonal::shared_ptr model
InvDepthFactorVariant3b This
shorthand for this class
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Vector evaluateError(const Pose3 &pose, const Vector3 &landmark, OptionalMatrixType H1, OptionalMatrixType H2) const override
Evaluate error h(x)-z and optionally derivatives.
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Non-linear factor base classes.
InvDepthFactorVariant3b()
Default constructor.
InvDepthFactorVariant3a This
shorthand for this class
static Key poseKey2(X(2))
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
Point2 measured_
2D measurement
~InvDepthFactorVariant3b() override
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
~InvDepthFactorVariant3a() override
InvDepthFactorVariant3a()
Default constructor.
NoiseModelFactor2< Pose3, Vector3 > Base
shorthand for base class type
The most common 5DOF 3D->2D calibration.
const Point2 & imagePoint() const
Matrix * OptionalMatrixType
static Key poseKey1(X(1))
static const CalibratedCamera camera(kDefaultPose)
void print(const std::string &s="InvDepthFactorVariant3a", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Cal3_S2::shared_ptr K_
shared pointer to calibration object
std::uint64_t Key
Integer nonlinear key type.
Point2 measured_
2D measurement
Vector inverseDepthError(const Pose3 &pose, const Vector3 &landmark) const
Cal3_S2::shared_ptr K_
shared pointer to calibration object
const Cal3_S2::shared_ptr calibration() const
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:02:28