26 #include <boost/optional.hpp> 35 template<
class POSE,
class LANDMARK,
class CALIBRATION = Cal3_S2>
41 boost::shared_ptr<CALIBRATION>
K_;
61 measured_(0, 0), throwCheirality_(false), verboseCheirality_(false) {
76 boost::optional<POSE> body_P_sensor = boost::none) :
77 Base(model, poseKey, pointKey), measured_(measured), K_(K), body_P_sensor_(body_P_sensor),
78 throwCheirality_(false), verboseCheirality_(false) {}
95 boost::optional<POSE> body_P_sensor = boost::none) :
96 Base(model, poseKey, pointKey), measured_(measured), K_(K), body_P_sensor_(body_P_sensor),
97 throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {}
113 std::cout <<
s <<
"GenericProjectionFactor, z = ";
115 if(this->body_P_sensor_)
116 this->body_P_sensor_->print(
" sensor pose in body frame: ");
122 const This *
e =
dynamic_cast<const This*
>(&
p);
126 && this->K_->equals(*e->K_,
tol)
127 && ((!body_P_sensor_ && !e->body_P_sensor_) || (body_P_sensor_ && e->body_P_sensor_ && body_P_sensor_->
equals(*e->body_P_sensor_)));
132 boost::optional<Matrix&> H1 = boost::none, boost::optional<Matrix&> H2 = boost::none)
const override {
140 return reprojectionError;
150 if (H1) *H1 = Matrix::Zero(2,6);
151 if (H2) *H2 = Matrix::Zero(2,3);
152 if (verboseCheirality_)
155 if (throwCheirality_)
158 return Vector2::Constant(2.0 * K_->fx());
181 template<
class ARCHIVE>
183 ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
184 ar & BOOST_SERIALIZATION_NVP(measured_);
185 ar & BOOST_SERIALIZATION_NVP(K_);
186 ar & BOOST_SERIALIZATION_NVP(body_P_sensor_);
187 ar & BOOST_SERIALIZATION_NVP(throwCheirality_);
188 ar & BOOST_SERIALIZATION_NVP(verboseCheirality_);
196 template<
class POSE,
class LANDMARK,
class CALIBRATION>
198 public Testable<GenericProjectionFactor<POSE, LANDMARK, CALIBRATION> > {
bool equals(const This &other, double tol=1e-9) const
check equality
const boost::shared_ptr< CALIBRATION > calibration() const
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
NoiseModelFactor2< POSE, LANDMARK > Base
shorthand for base class type
noiseModel::Diagonal::shared_ptr model
void serialize(ARCHIVE &ar, const unsigned int)
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
static const KeyFormatter DefaultKeyFormatter
const gtsam::Key pointKey
GenericProjectionFactor(const Point2 &measured, const SharedNoiseModel &model, Key poseKey, Key pointKey, const boost::shared_ptr< CALIBRATION > &K, boost::optional< POSE > body_P_sensor=boost::none)
Point2 measured_
2D measurement
~GenericProjectionFactor() override
Base class for all pinhole cameras.
Class compose(const Class &g) const
const Point2 & measured() const
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
friend class boost::serialization::access
Serialization function.
boost::shared_ptr< This > shared_ptr
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
boost::optional< POSE > body_P_sensor_
The pose of the sensor in the body frame.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
Vector evaluateError(const Pose3 &pose, const Point3 &point, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
Evaluate error h(x)-z and optionally derivatives.
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Non-linear factor base classes.
boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
bool verboseCheirality() const
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none, OptionalJacobian< 2, DimK > Dcal=boost::none) const
project a 3D point from world coordinates into the image
GenericProjectionFactor< POSE, LANDMARK, CALIBRATION > This
shorthand for this class
GenericProjectionFactor(const Point2 &measured, const SharedNoiseModel &model, Key poseKey, Key pointKey, const boost::shared_ptr< CALIBRATION > &K, bool throwCheirality, bool verboseCheirality, boost::optional< POSE > body_P_sensor=boost::none)
#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)
bool throwCheirality() const
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
bool throwCheirality_
If true, rethrows Cheirality exceptions (default: false)
boost::shared_ptr< CALIBRATION > K_
shared pointer to calibration object
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 noexceptoverride
GenericProjectionFactor()
Default constructor.