32 template<
class POSE,
class LANDMARK,
class CALIBRATION = Cal3_S2>
38 std::shared_ptr<CALIBRATION>
K_;
47 typedef NoiseModelFactor3<POSE, POSE, LANDMARK>
Base;
50 using Base::evaluateError;
60 measured_(0.0, 0.0), throwCheirality_(false), verboseCheirality_(false) {
74 Key poseKey,
Key transformKey,
Key pointKey,
75 const std::shared_ptr<CALIBRATION>& K) :
76 Base(model, poseKey, transformKey, pointKey), measured_(measured), K_(K),
77 throwCheirality_(false), verboseCheirality_(false) {}
91 Key poseKey,
Key transformKey,
Key pointKey,
92 const std::shared_ptr<CALIBRATION>& K,
94 Base(model, poseKey, transformKey, pointKey), measured_(measured), K_(K),
95 throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {}
101 NonlinearFactor::shared_ptr
clone()
const override {
103 NonlinearFactor::shared_ptr(
new This(*
this))); }
110 void print(
const std::string& s =
"",
const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const override {
111 std::cout << s <<
"ProjectionFactorPPP, z = ";
118 const This *e =
dynamic_cast<const This*
>(&p);
120 && Base::equals(p, tol)
122 && this->K_->equals(*e->K_, tol);
132 Point2 reprojectionError(camera.project(point, H1, H3, {}) -
measured_);
135 return reprojectionError;
138 return camera.
project(point, H1, H3, {}) - measured_;
141 if (H1) *H1 = Matrix::Zero(2,6);
142 if (H2) *H2 = Matrix::Zero(2,6);
143 if (H3) *H3 = Matrix::Zero(2,3);
144 if (verboseCheirality_)
145 std::cout << e.what() <<
": Landmark " 146 << DefaultKeyFormatter(this->key2())
147 <<
" moved behind camera " 148 << DefaultKeyFormatter(this->key1())
150 if (throwCheirality_)
153 return Vector::Ones(2) * 2.0 * K_->fx();
174 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 175 friend class boost::serialization::access; 177 template<
class ARCHIVE>
178 void serialize(ARCHIVE & ar,
const unsigned int ) {
179 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
180 ar & BOOST_SERIALIZATION_NVP(measured_);
181 ar & BOOST_SERIALIZATION_NVP(K_);
182 ar & BOOST_SERIALIZATION_NVP(throwCheirality_);
183 ar & BOOST_SERIALIZATION_NVP(verboseCheirality_);
189 template<
class POSE,
class LANDMARK,
class CALIBRATION>
191 public Testable<ProjectionFactorPPP<POSE, LANDMARK, CALIBRATION> > {
Definition: NonlinearFactor.h:431
NoiseModelFactor3< POSE, POSE, LANDMARK > Base
shorthand for base class type
Definition: ProjectionFactorPPP.h:47
std::shared_ptr< CALIBRATION > K_
shared pointer to calibration object
Definition: ProjectionFactorPPP.h:38
bool verboseCheirality_
If true, prints text for Cheirality exceptions (default: false)
Definition: ProjectionFactorPPP.h:42
const std::shared_ptr< CALIBRATION > calibration() const
Definition: ProjectionFactorPPP.h:162
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:113
ProjectionFactorPPP< POSE, LANDMARK, CALIBRATION > This
shorthand for this class
Definition: ProjectionFactorPPP.h:53
Definition: Testable.h:152
Vector2 Point2
Definition: Point2.h:32
Definition: NonlinearFactor.h:68
bool verboseCheirality() const
Definition: ProjectionFactorPPP.h:167
Definition: ProjectionFactorPPP.h:33
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
Matrix * OptionalMatrixType
Definition: NonlinearFactor.h:55
bool throwCheirality_
If true, rethrows Cheirality exceptions (default: false)
Definition: ProjectionFactorPPP.h:41
GTSAM_EXPORT void print(const Matrix &A, const std::string &s, std::ostream &stream)
ProjectionFactorPPP(const Point2 &measured, const SharedNoiseModel &model, Key poseKey, Key transformKey, Key pointKey, const std::shared_ptr< CALIBRATION > &K, bool throwCheirality, bool verboseCheirality)
Definition: ProjectionFactorPPP.h:90
const Point2 & measured() const
Definition: ProjectionFactorPPP.h:157
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
~ProjectionFactorPPP() override
Definition: ProjectionFactorPPP.h:98
Definition: PinholeCamera.h:33
Definition: chartTesting.h:28
Vector evaluateError(const Pose3 &pose, const Pose3 &transform, const Point3 &point, OptionalMatrixType H1, OptionalMatrixType H2, OptionalMatrixType H3) const override
Evaluate error h(x)-z and optionally derivatives.
Definition: ProjectionFactorPPP.h:126
Non-linear factor base classes.
NonlinearFactor::shared_ptr clone() const override
Definition: ProjectionFactorPPP.h:101
ProjectionFactorPPP(const Point2 &measured, const SharedNoiseModel &model, Key poseKey, Key transformKey, Key pointKey, const std::shared_ptr< CALIBRATION > &K)
Definition: ProjectionFactorPPP.h:73
bool throwCheirality() const
Definition: ProjectionFactorPPP.h:170
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Definition: ProjectionFactorPPP.h:117
Point2 measured_
2D measurement
Definition: ProjectionFactorPPP.h:37
Definition: CalibratedCamera.h:34
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: ProjectionFactorPPP.h:110
Vector3 Point3
Definition: Point3.h:38
ProjectionFactorPPP()
Default constructor.
Definition: ProjectionFactorPPP.h:59
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Definition: ProjectionFactorPPP.h:56
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
The most common 5DOF 3D->2D calibration.