Go to the documentation of this file.
24 #include <gtsam_unstable/dllexport.h>
49 std::shared_ptr<Cal3_S2> K_;
56 bool verboseCheirality_;
62 typedef NoiseModelFactor3<Pose3, Pose3, Point3>
Base;
65 using Base::evaluateError;
78 throwCheirality_(false),
79 verboseCheirality_(false) {}
97 const std::shared_ptr<Cal3_S2>&
K,
104 throwCheirality_(
false),
105 verboseCheirality_(
false) {}
127 const std::shared_ptr<Cal3_S2>&
K,
bool throwCheirality,
128 bool verboseCheirality,
135 throwCheirality_(throwCheirality),
136 verboseCheirality_(verboseCheirality) {}
143 return std::static_pointer_cast<gtsam::NonlinearFactor>(
153 const std::string&
s =
"",
155 std::cout <<
s <<
"ProjectionFactorRollingShutter, z = ";
157 std::cout <<
" rolling shutter interpolation param = " << alpha_;
158 if (this->body_P_sensor_)
159 this->body_P_sensor_->print(
" sensor pose in body frame: ");
165 const This*
e =
dynamic_cast<const This*
>(&
p);
166 return e && Base::equals(
p,
tol) && (alpha_ ==
e->alpha()) &&
168 this->K_->equals(*
e->K_,
tol) &&
169 (this->throwCheirality_ ==
e->throwCheirality_) &&
170 (this->verboseCheirality_ ==
e->verboseCheirality_) &&
171 ((!body_P_sensor_ && !
e->body_P_sensor_) ||
172 (body_P_sensor_ &&
e->body_P_sensor_ &&
173 body_P_sensor_->equals(*
e->body_P_sensor_)));
185 inline const std::shared_ptr<Cal3_S2>
calibration()
const {
return K_; }
188 inline double alpha()
const {
return alpha_; }
197 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
198 friend class boost::serialization::access;
200 template <
class ARCHIVE>
201 void serialize(ARCHIVE& ar,
const unsigned int ) {
202 ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(
Base);
203 ar& BOOST_SERIALIZATION_NVP(measured_);
204 ar& BOOST_SERIALIZATION_NVP(alpha_);
205 ar& BOOST_SERIALIZATION_NVP(K_);
206 ar& BOOST_SERIALIZATION_NVP(body_P_sensor_);
207 ar& BOOST_SERIALIZATION_NVP(throwCheirality_);
208 ar& BOOST_SERIALIZATION_NVP(verboseCheirality_);
219 :
public Testable<ProjectionFactorRollingShutter> {};
std::shared_ptr< This > shared_ptr
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
Point2 measured_
2D measurement
const gtsam::Key pointKey
Array< double, 1, 3 > e(1./3., 0.5, 2.)
The most common 5DOF 3D->2D calibration.
NoiseModelFactor3< Pose3, Pose3, Point3 > Base
shorthand for base class type
bool equals(const NonlinearFactor &p, double tol=1e-9) const override
equals
static Pose3 body_P_sensor(Rot3::RzRyRx(-M_PI_2, 0.0, -M_PI_2), Point3(0.25, -0.10, 1.0))
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Calibrated camera for which only pose is unknown.
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
std::optional< Pose3 > body_P_sensor_
The pose of the sensor in the body frame.
ProjectionFactorRollingShutter This
shorthand for this class
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
bool verboseCheirality() const
Base class for all pinhole cameras.
noiseModel::Base::shared_ptr SharedNoiseModel
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW
virtual ~ProjectionFactorRollingShutter()
noiseModel::Diagonal::shared_ptr model
ProjectionFactorRollingShutter()
Default constructor.
Non-linear factor base classes.
std::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
ProjectionFactorRollingShutter(const Point2 &measured, double alpha, const SharedNoiseModel &model, Key poseKey_a, Key poseKey_b, Key pointKey, const std::shared_ptr< Cal3_S2 > &K, std::optional< Pose3 > body_P_sensor={})
const Point2 & measured() const
void Print(const CONTAINER &keys, const string &s, const KeyFormatter &keyFormatter)
Matrix * OptionalMatrixType
const std::shared_ptr< Cal3_S2 > calibration() const
gtsam::NonlinearFactor::shared_ptr clone() const override
std::uint64_t Key
Integer nonlinear key type.
ProjectionFactorRollingShutter(const Point2 &measured, double alpha, const SharedNoiseModel &model, Key poseKey_a, Key poseKey_b, Key pointKey, const std::shared_ptr< Cal3_S2 > &K, bool throwCheirality, bool verboseCheirality, std::optional< Pose3 > body_P_sensor={})
bool throwCheirality() const
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:03:53