Go to the documentation of this file.
92 void print(
const std::string&
s =
"")
const;
101 enum { dimension = 7 };
102 inline static size_t Dim() {
return dimension; }
103 inline size_t dim()
const {
return dimension; }
114 : U_(
U), s_(
s), V_(
V) {}
145 : E_(), fa_(1.0), fb_(1.0), ca_(0.0, 0.0), cb_(0.0, 0.0) {}
156 double fa,
double fb,
const Point2& ca,
158 : E_(
E), fa_(fa), fb_(fb), ca_(ca), cb_(cb) {}
167 void print(
const std::string&
s =
"")
const;
175 enum { dimension = 7 };
176 inline static size_t Dim() {
return dimension; }
177 inline size_t dim()
const {
return dimension; }
194 const Matrix3& Fcb,
const Point2& pb);
198 template <
typename F>
double fa_
Focal length for left camera.
double s_
Scalar parameter for S.
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.
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 Fri Nov 1 2024 03:32:33