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) {
100 Key poseKey,
Key pointKey,
const std::shared_ptr<CALIBRATION>& K,
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_)));
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_)
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
std::string serialize(const T &input)
serializes to a string
noiseModel::Diagonal::shared_ptr model
const Point2 & measured() const
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
virtual Vector evaluateError(const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
std::optional< POSE > body_P_sensor_
The pose of the sensor in the body frame.
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={})
NoiseModelFactorN< POSE, LANDMARK > Base
shorthand for base class type
static const KeyFormatter DefaultKeyFormatter
const gtsam::Key pointKey
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Point2 measured_
2D measurement
~GenericProjectionFactor() override
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
GenericProjectionFactor(const Point2 &measured, const SharedNoiseModel &model, Key poseKey, Key pointKey, const std::shared_ptr< CALIBRATION > &K, std::optional< POSE > body_P_sensor={})
const std::shared_ptr< CALIBRATION > calibration() const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
const std::optional< POSE > & body_P_sensor() const
bool throwCheirality() const
Class compose(const Class &g) const
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Vector evaluateError(const Pose3 &pose, const Point3 &point, OptionalMatrixType H1, OptionalMatrixType H2) const override
Evaluate error h(x)-z and optionally derivatives.
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Non-linear factor base classes.
std::shared_ptr< This > shared_ptr
bool verboseCheirality() const
GenericProjectionFactor< POSE, LANDMARK, CALIBRATION > This
shorthand for this class
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
gtsam::NonlinearFactor::shared_ptr clone() const override
static const CalibratedCamera camera(kDefaultPose)
bool verboseCheirality_
If true, prints text for Cheirality exceptions (default: false)
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
bool throwCheirality_
If true, rethrows Cheirality exceptions (default: false)
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
bool equals(const This &other, double tol=1e-9) const
check equality
GenericProjectionFactor()
Default constructor.