38 template <
class POSE = Pose3,
class LANDMARK =
Point3,
39 class CALIBRATION = Cal3_S2>
45 std::shared_ptr<CALIBRATION>
K_;
68 measured_(0, 0), throwCheirality_(false), verboseCheirality_(false) {
82 Key poseKey,
Key pointKey,
const std::shared_ptr<CALIBRATION>& K,
100 Key poseKey,
Key pointKey,
const std::shared_ptr<CALIBRATION>& K,
110 gtsam::NonlinearFactor::shared_ptr
clone()
const override {
112 gtsam::NonlinearFactor::shared_ptr(
new This(*
this))); }
119 void print(
const std::string& s =
"",
const KeyFormatter& keyFormatter = DefaultKeyFormatter)
const override {
120 std::cout << s <<
"GenericProjectionFactor, z = ";
122 if(this->body_P_sensor_)
123 this->body_P_sensor_->print(
" sensor pose in body frame: ");
129 const This *e =
dynamic_cast<const This*
>(&p);
133 && this->K_->equals(*e->K_, tol)
134 && ((!body_P_sensor_ && !e->body_P_sensor_) || (body_P_sensor_ && e->body_P_sensor_ && body_P_sensor_->
equals(*e->body_P_sensor_)));
145 Point2 reprojectionError(camera.project(point, H1, H2, {}) -
measured_);
147 return reprojectionError;
150 return camera.
project(point, H1, H2, {}) - measured_;
154 return camera.
project(point, H1, H2, {}) - measured_;
157 if (H1) *H1 = Matrix::Zero(2,6);
158 if (H2) *H2 = Matrix::Zero(2,3);
159 if (verboseCheirality_)
160 std::cout << e.what() <<
": Landmark "<< DefaultKeyFormatter(this->key2()) <<
161 " moved behind camera " << DefaultKeyFormatter(this->key1()) << std::endl;
162 if (throwCheirality_)
165 return Vector2::Constant(2.0 * K_->fx());
191 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 192 friend class boost::serialization::access; 194 template<
class ARCHIVE>
195 void serialize(ARCHIVE & ar,
const unsigned int ) {
196 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
197 ar & BOOST_SERIALIZATION_NVP(measured_);
198 ar & BOOST_SERIALIZATION_NVP(K_);
199 ar & BOOST_SERIALIZATION_NVP(body_P_sensor_);
200 ar & BOOST_SERIALIZATION_NVP(throwCheirality_);
201 ar & BOOST_SERIALIZATION_NVP(verboseCheirality_);
210 template<
class POSE,
class LANDMARK,
class CALIBRATION>
212 public Testable<GenericProjectionFactor<POSE, LANDMARK, CALIBRATION> > {
std::shared_ptr< CALIBRATION > K_
shared pointer to calibration object
Definition: ProjectionFactor.h:45
Definition: NonlinearFactor.h:431
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:113
const Point2 & measured() const
Definition: ProjectionFactor.h:169
Definition: Testable.h:152
Vector2 Point2
Definition: Point2.h:32
virtual Vector evaluateError(const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
Definition: NonlinearFactor.h:68
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
Definition: ProjectionFactor.h:64
std::optional< POSE > body_P_sensor_
The pose of the sensor in the body frame.
Definition: ProjectionFactor.h:46
GenericProjectionFactor(const Point2 &measured, const SharedNoiseModel &model, Key poseKey, Key pointKey, const std::shared_ptr< CALIBRATION > &K, bool throwCheirality, bool verboseCheirality, std::optional< POSE > body_P_sensor={})
Definition: ProjectionFactor.h:99
NoiseModelFactorN< POSE, LANDMARK > Base
shorthand for base class type
Definition: ProjectionFactor.h:55
Point2 measured_
2D measurement
Definition: ProjectionFactor.h:44
~GenericProjectionFactor() override
Definition: ProjectionFactor.h:107
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
GenericProjectionFactor(const Point2 &measured, const SharedNoiseModel &model, Key poseKey, Key pointKey, const std::shared_ptr< CALIBRATION > &K, std::optional< POSE > body_P_sensor={})
Definition: ProjectionFactor.h:81
const std::shared_ptr< CALIBRATION > calibration() const
Definition: ProjectionFactor.h:174
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Definition: ProjectionFactor.h:128
const std::optional< POSE > & body_P_sensor() const
Definition: ProjectionFactor.h:179
bool throwCheirality() const
Definition: ProjectionFactor.h:187
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: PinholeCamera.h:33
Definition: chartTesting.h:28
Vector evaluateError(const Pose3 &pose, const Point3 &point, OptionalMatrixType H1, OptionalMatrixType H2) const override
Evaluate error h(x)-z and optionally derivatives.
Definition: ProjectionFactor.h:138
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Non-linear factor base classes.
bool verboseCheirality() const
Definition: ProjectionFactor.h:184
GenericProjectionFactor< POSE, LANDMARK, CALIBRATION > This
shorthand for this class
Definition: ProjectionFactor.h:61
Definition: CalibratedCamera.h:34
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:284
Vector3 Point3
Definition: Point3.h:38
gtsam::NonlinearFactor::shared_ptr clone() const override
Definition: ProjectionFactor.h:110
bool verboseCheirality_
If true, prints text for Cheirality exceptions (default: false)
Definition: ProjectionFactor.h:50
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: ProjectionFactor.h:119
bool throwCheirality_
If true, rethrows Cheirality exceptions (default: false)
Definition: ProjectionFactor.h:49
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
Definition: ProjectionFactor.h:40
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
The most common 5DOF 3D->2D calibration.
bool equals(const This &other, double tol=1e-9) const
check equality
GenericProjectionFactor()
Default constructor.
Definition: ProjectionFactor.h:67