35 typedef NoiseModelFactor2<Pose3, Vector6>
Base;
38 using Base::evaluateError;
48 measured_(0.0, 0.0), K_(new
Cal3_S2(444, 555, 666, 777, 888)) {
61 Base(model, poseKey, landmarkKey), measured_(measured), K_(K) {}
71 void print(
const std::string&
s =
"InvDepthFactorVariant1",
79 const This *
e =
dynamic_cast<const This*
>(&
p);
81 && Base::equals(p,
tol)
83 && this->K_->equals(*e->K_,
tol);
100 return Vector::Ones(2) * 2.0 * K_->fx();
102 return (
Vector(1) << 0.0).finished();
110 (*H1) = numericalDerivative11<Vector, Pose3>(
112 std::placeholders::_1, landmark),
116 (*H2) = numericalDerivative11<Vector, Vector6>(
136 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 137 friend class boost::serialization::access; 139 template<
class ARCHIVE>
140 void serialize(ARCHIVE & ar,
const unsigned int ) {
141 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
142 ar & BOOST_SERIALIZATION_NVP(measured_);
143 ar & BOOST_SERIALIZATION_NVP(K_);
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Jet< T, N > cos(const Jet< T, N > &f)
const Point2 & imagePoint() const
~InvDepthFactorVariant1() override
std::string serialize(const T &input)
serializes to a string
InvDepthFactorVariant1()
Default constructor.
noiseModel::Diagonal::shared_ptr model
Point2 measured_
2D measurement
Vector evaluateError(const Pose3 &pose, const Vector6 &landmark, OptionalMatrixType H1, OptionalMatrixType H2) const override
Evaluate error h(x)-z and optionally derivatives.
Jet< T, N > sin(const Jet< T, N > &f)
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
void print(const std::string &s="InvDepthFactorVariant1", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Some functions to compute numerical derivatives.
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
static const KeyFormatter DefaultKeyFormatter
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
Matrix * OptionalMatrixType
std::shared_ptr< Cal3_S2 > shared_ptr
Vector inverseDepthError(const Pose3 &pose, const Vector6 &landmark) const
InvDepthFactorVariant1 This
shorthand for this class
NoiseModelFactor2< Pose3, Vector6 > Base
shorthand for base class type
Array< double, 1, 3 > e(1./3., 0.5, 2.)
The most common 5DOF 3D->2D calibration.
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
const Cal3_S2::shared_ptr calibration() const
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Non-linear factor base classes.
Cal3_S2::shared_ptr K_
shared pointer to calibration object
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
static const CalibratedCamera camera(kDefaultPose)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
InvDepthFactorVariant1(const Key poseKey, const Key landmarkKey, const Point2 &measured, const Cal3_S2::shared_ptr &K, const SharedNoiseModel &model)
std::uint64_t Key
Integer nonlinear key type.
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
noiseModel::Base::shared_ptr SharedNoiseModel
The most common 5DOF 3D->2D calibration.
const char * what() const noexcept override