46 template <
typename Cal,
size_t Dim>
52 Matrix22 H_uncal_pn, H_uncal_pn_inv;
55 calibration.uncalibrate(pn, Dcal ? &H_uncal_K :
nullptr, H_uncal_pn);
57 H_uncal_pn_inv = H_uncal_pn.inverse();
59 if (Dp) *Dp = H_uncal_pn_inv;
60 if (Dcal) *Dcal = -H_uncal_pn_inv * H_uncal_K;
71 double fx_ = 1.0f, fy_ = 1.0f;
73 double u0_ = 0.0f, v0_ = 0.0f;
76 enum { dimension = 5 };
88 : fx_(fx), fy_(fy), s_(s), u0_(u0), v0_(v0) {}
92 : fx_(d(0)), fy_(d(1)), s_(d(2)), u0_(d(3)), v0_(d(4)) {}
118 Cal3(
const std::string& path);
125 GTSAM_EXPORT
friend std::ostream&
operator<<(std::ostream&
os,
129 virtual void print(
const std::string&
s =
"")
const;
139 inline double fx()
const {
return fx_; }
142 inline double fy()
const {
return fy_; }
148 inline double skew()
const {
return s_; }
151 inline double px()
const {
return u0_; }
154 inline double py()
const {
return v0_; }
162 v << fx_, fy_, s_, u0_, v0_;
167 virtual Matrix3
K()
const {
169 K << fx_, s_, u0_, 0.0, fy_, v0_, 0.0, 0.0, 1.0;
173 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41 175 Matrix3
matrix()
const {
return K(); }
182 inline virtual size_t dim()
const {
return Dim(); }
185 inline static size_t Dim() {
return dimension; }
193 friend class boost::serialization::access;
194 template <
class Archive>
196 ar& BOOST_SERIALIZATION_NVP(fx_);
197 ar& BOOST_SERIALIZATION_NVP(fy_);
198 ar& BOOST_SERIALIZATION_NVP(s_);
199 ar& BOOST_SERIALIZATION_NVP(u0_);
200 ar& BOOST_SERIALIZATION_NVP(v0_);
void print(const Matrix &A, const string &s, ostream &stream)
static size_t Dim()
return DOF, dimensionality of tangent space
double fy() const
focal length y
void calibrateJacobians(const Cal &calibration, const Point2 &pn, OptionalJacobian< 2, Dim > Dcal=boost::none, OptionalJacobian< 2, 2 > Dp=boost::none)
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
double aspectRatio() const
aspect ratio
virtual Matrix3 K() const
return calibration matrix K
virtual ~Cal3()
Virtual destructor.
double py() const
image center in y
void serialize(Archive &ar, const unsigned int)
boost::shared_ptr< Cal3 > shared_ptr
virtual size_t dim() const
return DOF, dimensionality of tangent space
Cal3(double fx, double fy, double s, double u0, double v0)
constructor from doubles
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Vector5 vector() const
vectorized form (column-wise)
Point2 principalPoint() const
return the principal point
ofstream os("timeSchurFactors.csv")
double px() const
image center in x
double fx() const
focal length x
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
The matrix class, also used for vectors and row-vectors.
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
Cal3(const Vector5 &d)
constructor from vector