Go to the documentation of this file.
96 void print(
const std::string&
s =
"")
const;
100 bool equals(
const FundamentalMatrix&
other,
double tol = 1
e-9)
const;
105 inline constexpr
static auto dimension = 7;
106 inline static size_t Dim() {
return dimension; }
107 inline size_t dim()
const {
return dimension; }
118 : U_(
U), s_(
s), V_(
V) {}
149 : E_(), fa_(1.0), fb_(1.0), ca_(0.0, 0.0), cb_(0.0, 0.0) {}
160 double fa,
double fb,
const Point2& ca,
162 : E_(
E), fa_(fa), fb_(fb), ca_(ca), cb_(cb) {}
174 void print(
const std::string&
s =
"")
const;
177 bool equals(
const SimpleFundamentalMatrix&
other,
double tol = 1
e-9)
const;
182 inline constexpr
static auto dimension = 7;
183 inline static size_t Dim() {
return dimension; }
184 inline size_t dim()
const {
return dimension; }
201 const Matrix3& Fcb,
const Point2& pb);
205 template <
typename F>
double fa_
Focal length for left camera.
double s_
Scalar parameter for S.
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
const EIGEN_DEVICE_FUNC InverseReturnType inverse() const
Point2 transferToC(const Point2 &pa, const Point2 &pb)
Transfers a point from cameras a,b to camera c.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Point2 ca_
Principal point for left camera.
SimpleFundamentalMatrix(const EssentialMatrix &E, double fa, double fb, const Point2 &ca, const Point2 &cb)
Construct from essential matrix and focal lengths.
def retract(a, np.ndarray xi)
FundamentalMatrix(const Rot3 &U, double s, const Rot3 &V)
Private constructor for internal use.
Point2 cb_
Principal point for right camera.
Both ManifoldTraits and Testable.
Point2 EpipolarTransfer(const Matrix3 &Fca, const Point2 &pa, const Matrix3 &Fcb, const Point2 &pb)
Transfer projections from cameras a and b to camera c.
Point2 transferToB(const Point2 &pa, const Point2 &pc)
Transfers a point from camera a,c to camera b.
3D rotation represented as a rotation matrix or quaternion
void print(const Matrix &A, const string &s, ostream &stream)
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
SimpleFundamentalMatrix()
Default constructor.
Special class for optional Jacobian arguments.
int RealScalar int RealScalar int RealScalar * pc
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
FundamentalMatrix(const Matrix3 &Ka, const EssentialMatrix &E, const Matrix3 &Kb)
Construct from essential matrix and calibration matrices.
Class for representing a simple fundamental matrix.
FundamentalMatrix(const Matrix3 &Ka, const Pose3 &aPb, const Matrix3 &Kb)
Construct from calibration matrices Ka, Kb, and pose aPb.
Point2 transferToA(const Point2 &pb, const Point2 &pc)
Transfers a point from cameras b,c to camera a.
FundamentalMatrix()
Default constructor.
Represents a fundamental matrix in computer vision, which encodes the epipolar geometry between two v...
Values initialize(const NonlinearFactorGraph &graph, bool useOdometricPath)
EssentialMatrix E_
Essential matrix.
double fb_
Focal length for right camera.
gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:11:33