Go to the documentation of this file.
38 template <
class POSE =
Pose3,
class LANDMARK =
Point3,
39 class CALIBRATION = Cal3_S2>
45 std::shared_ptr<CALIBRATION>
K_;
111 return std::static_pointer_cast<gtsam::NonlinearFactor>(
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)
147 return reprojectionError;
157 if (H1) *H1 = Matrix::Zero(2,6);
158 if (H2) *H2 = Matrix::Zero(2,3);
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);
198 ar & BOOST_SERIALIZATION_NVP(
K_);
210 template<
class POSE,
class LANDMARK,
class CALIBRATION>
212 public Testable<GenericProjectionFactor<POSE, LANDMARK, CALIBRATION> > {
std::shared_ptr< This > shared_ptr
gtsam::NonlinearFactor::shared_ptr clone() const override
const std::shared_ptr< CALIBRATION > calibration() const
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
const gtsam::Key pointKey
Array< double, 1, 3 > e(1./3., 0.5, 2.)
The most common 5DOF 3D->2D calibration.
virtual Vector evaluateError(const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
bool throwCheirality() const
GenericProjectionFactor(const Point2 &measured, const SharedNoiseModel &model, Key poseKey, Key pointKey, const std::shared_ptr< CALIBRATION > &K, std::optional< POSE > body_P_sensor={})
GenericProjectionFactor()
Default constructor.
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
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={})
bool verboseCheirality_
If true, prints text for Cheirality exceptions (default: false)
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Vector evaluateError(const Pose3 &pose, const Point3 &point, OptionalMatrixType H1, OptionalMatrixType H2) const override
Evaluate error h(x)-z and optionally derivatives.
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
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
Base class for all pinhole cameras.
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
~GenericProjectionFactor() override
noiseModel::Base::shared_ptr SharedNoiseModel
NoiseModelFactorN< POSE, LANDMARK > Base
shorthand for base class type
std::optional< POSE > body_P_sensor_
The pose of the sensor in the body frame.
noiseModel::Diagonal::shared_ptr model
bool throwCheirality_
If true, rethrows Cheirality exceptions (default: false)
GenericProjectionFactor< POSE, LANDMARK, CALIBRATION > This
shorthand for this class
Non-linear factor base classes.
Point2 measured_
2D measurement
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
const Point2 & measured() const
std::shared_ptr< CALIBRATION > K_
shared pointer to calibration object
Matrix * OptionalMatrixType
bool verboseCheirality() const
static const CalibratedCamera camera(kDefaultPose)
const std::optional< POSE > & body_P_sensor() const
std::uint64_t Key
Integer nonlinear key type.
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:03:53