Go to the documentation of this file.
31 template<
class POSE,
class LANDMARK>
99 return std::static_pointer_cast<gtsam::NonlinearFactor>(
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);
153 return Vector3::Constant(2.0 *
K_->fx());
178 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
180 friend class boost::serialization::access;
181 template<
class Archive>
182 void serialize(Archive & ar,
const unsigned int ) {
184 ar & boost::serialization::make_nvp(
"NoiseModelFactor2",
185 boost::serialization::base_object<Base>(*
this));
187 ar & BOOST_SERIALIZATION_NVP(
K_);
196 template<
class T1,
class T2>
void print(const std::string &s="") const
std::shared_ptr< This > shared_ptr
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Array< double, 1, 3 > e(1./3., 0.5, 2.)
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
bool throwCheirality_
If true, rethrows Cheirality exceptions (default: false)
const StereoPoint2 & measured() const
static StereoCamera stereoCam(camPose, K)
virtual Vector evaluateError(const ValueTypes &... x, OptionalMatrixTypeT< ValueTypes >... H) const=0
NoiseModelFactorN< POSE, LANDMARK > Base
typedef for base class
GenericStereoFactor(const StereoPoint2 &measured, const SharedNoiseModel &model, Key poseKey, Key landmarkKey, const Cal3_S2Stereo::shared_ptr &K, std::optional< POSE > body_P_sensor={})
bool throwCheirality() const
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={})
bool equals(const StereoPoint2 &q, double tol=1e-9) const
std::shared_ptr< GenericStereoFactor > shared_ptr
typedef for shared pointer to this object
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
bool verboseCheirality_
If true, prints text for Cheirality exceptions (default: false)
GenericStereoFactor< POSE, LANDMARK > This
typedef for this class (with templates)
Vector evaluateError(const Pose3 &pose, const Point3 &point, OptionalMatrixType H1, OptionalMatrixType H2) const override
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
POSE CamPose
typedef for Pose Lie Value type
const Cal3_S2Stereo::shared_ptr calibration() const
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
bool verboseCheirality() const
std::optional< POSE > body_P_sensor_
The pose of the sensor in the body frame.
std::shared_ptr< Cal3_S2Stereo > shared_ptr
const std::optional< POSE > & body_P_sensor() const
bool equals(const NonlinearFactor &f, double tol=1e-9) const override
StereoPoint2 measured_
the measurement
static const Pose3 T2(Rot3::Rodrigues(0.3, 0.2, 0.1), P2)
noiseModel::Base::shared_ptr SharedNoiseModel
noiseModel::Diagonal::shared_ptr model
~GenericStereoFactor() override
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Non-linear factor base classes.
The most common 5DOF 3D->2D calibration, stereo version.
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Matrix * OptionalMatrixType
static const Similarity3 T1(R, Point3(3.5, -8.2, 4.2), 1)
std::uint64_t Key
Integer nonlinear key type.
Cal3_S2Stereo::shared_ptr K_
shared pointer to calibration
gtsam::NonlinearFactor::shared_ptr clone() const override
A Stereo Camera based on two Simple Cameras.
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:05:00