30 template<
class POSE,
class LANDMARK>
48 typedef boost::shared_ptr<GenericStereoFactor>
shared_ptr;
55 throwCheirality_(false), verboseCheirality_(false) {}
68 boost::optional<POSE> body_P_sensor = boost::none) :
69 Base(model, poseKey, landmarkKey), measured_(measured), K_(K), body_P_sensor_(body_P_sensor),
70 throwCheirality_(false), verboseCheirality_(false) {}
86 boost::optional<POSE> body_P_sensor = boost::none) :
87 Base(model, poseKey, landmarkKey), measured_(measured), K_(K), body_P_sensor_(body_P_sensor),
88 throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {}
105 measured_.
print(
s +
".z");
106 if(this->body_P_sensor_)
107 this->body_P_sensor_->print(
" sensor pose in body frame: ");
123 boost::optional<Matrix&> H1 = boost::none, boost::optional<Matrix&> H2 = boost::none)
const override {
131 return reprojectionError.
vector();
141 if (H1) *H1 = Matrix::Zero(3,6);
143 if (verboseCheirality_)
146 if (throwCheirality_)
149 return Vector3::Constant(2.0 * K_->fx());
171 template<
class Archive>
173 ar & boost::serialization::make_nvp(
"NoiseModelFactor2",
174 boost::serialization::base_object<Base>(*
this));
175 ar & BOOST_SERIALIZATION_NVP(measured_);
176 ar & BOOST_SERIALIZATION_NVP(K_);
177 ar & BOOST_SERIALIZATION_NVP(body_P_sensor_);
178 ar & BOOST_SERIALIZATION_NVP(throwCheirality_);
179 ar & BOOST_SERIALIZATION_NVP(verboseCheirality_);
184 template<
class T1,
class T2>
NoiseModelFactor2< POSE, LANDMARK > Base
typedef for base class
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
~GenericStereoFactor() override
StereoPoint2 measured_
the measurement
noiseModel::Diagonal::shared_ptr model
GenericStereoFactor(const StereoPoint2 &measured, const SharedNoiseModel &model, Key poseKey, Key landmarkKey, const Cal3_S2Stereo::shared_ptr &K, boost::optional< POSE > body_P_sensor=boost::none)
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
Pose2 T2(M_PI/2.0, Point2(0.0, 2.0))
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
bool verboseCheirality() const
Class compose(const Class &g) const
boost::shared_ptr< Cal3_S2Stereo > shared_ptr
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
const StereoPoint2 & measured() const
boost::shared_ptr< This > shared_ptr
gtsam::NonlinearFactor::shared_ptr clone() const override
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
void print(const std::string &s="") const
boost::optional< POSE > body_P_sensor_
The pose of the sensor in the body frame.
const Cal3_S2Stereo::shared_ptr calibration() const
bool throwCheirality() const
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
bool throwCheirality_
If true, rethrows Cheirality exceptions (default: false)
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Vector evaluateError(const Pose3 &pose, const Point3 &point, boost::optional< Matrix & > H1=boost::none, boost::optional< Matrix & > H2=boost::none) const override
A Stereo Camera based on two Simple Cameras.
Non-linear factor base classes.
bool equals(const StereoPoint2 &q, double tol=1e-9) const
StereoPoint2 project(const Point3 &point) const
Project 3D point to StereoPoint2 (uL,uR,v)
GenericStereoFactor(const StereoPoint2 &measured, const SharedNoiseModel &model, Key poseKey, Key landmarkKey, const Cal3_S2Stereo::shared_ptr &K, bool throwCheirality, bool verboseCheirality, boost::optional< POSE > body_P_sensor=boost::none)
Pose2 T1(M_PI/4.0, Point2(sqrt(0.5), sqrt(0.5)))
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
friend class boost::serialization::access
std::uint64_t Key
Integer nonlinear key type.
boost::shared_ptr< GenericStereoFactor > shared_ptr
typedef for shared pointer to this object
static StereoCamera stereoCam(camPose, K)
noiseModel::Base::shared_ptr SharedNoiseModel
void serialize(Archive &ar, const unsigned int)