31 template<
class POSE,
class LANDMARK>
59 throwCheirality_(false), verboseCheirality_(false) {}
109 measured_.
print(
s +
".z");
110 if(this->body_P_sensor_)
111 this->body_P_sensor_->print(
" sensor pose in body frame: ");
135 return reprojectionError.
vector();
145 if (H1) *H1 = Matrix::Zero(3,6);
147 if (verboseCheirality_)
150 if (throwCheirality_)
153 return Vector3::Constant(2.0 * K_->fx());
173 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 175 friend class boost::serialization::access;
176 template<
class Archive>
177 void serialize(Archive & ar,
const unsigned int ) {
179 ar & boost::serialization::make_nvp(
"NoiseModelFactor2",
180 boost::serialization::base_object<Base>(*
this));
181 ar & BOOST_SERIALIZATION_NVP(measured_);
182 ar & BOOST_SERIALIZATION_NVP(K_);
183 ar & BOOST_SERIALIZATION_NVP(body_P_sensor_);
184 ar & BOOST_SERIALIZATION_NVP(throwCheirality_);
185 ar & BOOST_SERIALIZATION_NVP(verboseCheirality_);
191 template<
class T1,
class T2>
const Cal3_S2Stereo::shared_ptr calibration() const
bool verboseCheirality() const
std::optional< POSE > body_P_sensor_
The pose of the sensor in the body frame.
~GenericStereoFactor() override
StereoPoint2 measured_
the measurement
std::string serialize(const T &input)
serializes to a string
noiseModel::Diagonal::shared_ptr model
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
virtual Vector evaluateError(const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
static Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0))
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
static const Pose3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2)
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
static const KeyFormatter DefaultKeyFormatter
Cal3_S2Stereo::shared_ptr K_
shared pointer to calibration
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Matrix * OptionalMatrixType
void print(const std::string &s="") const
The most common 5DOF 3D->2D calibration, stereo version.
gtsam::NonlinearFactor::shared_ptr clone() const override
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
const StereoPoint2 & measured() const
StereoPoint2 project(const Point3 &point) const
Project 3D point to StereoPoint2 (uL,uR,v)
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.
std::shared_ptr< Cal3_S2Stereo > shared_ptr
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
bool throwCheirality_
If true, rethrows Cheirality exceptions (default: false)
bool throwCheirality() const
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
GenericStereoFactor(const StereoPoint2 &measured, const SharedNoiseModel &model, Key poseKey, Key landmarkKey, const Cal3_S2Stereo::shared_ptr &K, bool throwCheirality, bool verboseCheirality, std::optional< POSE > body_P_sensor={})
A Stereo Camera based on two Simple Cameras.
Non-linear factor base classes.
NoiseModelFactorN< POSE, LANDMARK > Base
typedef for base class
static const Similarity3 T1(R, Point3(3.5, -8.2, 4.2), 1)
GenericStereoFactor(const StereoPoint2 &measured, const SharedNoiseModel &model, Key poseKey, Key landmarkKey, const Cal3_S2Stereo::shared_ptr &K, std::optional< POSE > body_P_sensor={})
std::shared_ptr< This > shared_ptr
std::shared_ptr< GenericStereoFactor > shared_ptr
typedef for shared pointer to this object
GenericStereoFactor< POSE, LANDMARK > This
typedef for this class (with templates)
bool verboseCheirality_
If true, prints text for Cheirality exceptions (default: false)
POSE CamPose
typedef for Pose Lie Value type
std::uint64_t Key
Integer nonlinear key type.
Vector evaluateError(const Pose3 &pose, const Point3 &point, OptionalMatrixType H1, OptionalMatrixType H2) const override
static StereoCamera stereoCam(camPose, K)
noiseModel::Base::shared_ptr SharedNoiseModel
bool equals(const StereoPoint2 &q, double tol=1e-9) const