FundamentalMatrix.h
Go to the documentation of this file.
1 /*
2  * @file FundamentalMatrix.h
3  * @brief FundamentalMatrix classes
4  * @author Frank Dellaert
5  * @date October 2024
6  */
7 
8 #pragma once
9 
12 #include <gtsam/geometry/Rot3.h>
13 #include <gtsam/geometry/Unit3.h>
14 
15 namespace gtsam {
16 
29 class GTSAM_EXPORT FundamentalMatrix {
30  private:
31  Rot3 U_;
32  double s_;
33  Rot3 V_;
34 
35  public:
37  FundamentalMatrix() : U_(Rot3()), s_(1.0), V_(Rot3()) {}
38 
45  FundamentalMatrix(const Matrix3& U, double s, const Matrix3& V);
46 
55  FundamentalMatrix(const Matrix3& F);
56 
69  FundamentalMatrix(const Matrix3& Ka, const EssentialMatrix& E,
70  const Matrix3& Kb)
71  : FundamentalMatrix(Ka.transpose().inverse() * E.matrix() *
72  Kb.inverse()) {}
73 
84  FundamentalMatrix(const Matrix3& Ka, const Pose3& aPb, const Matrix3& Kb)
85  : FundamentalMatrix(Ka, EssentialMatrix::FromPose3(aPb), Kb) {}
86 
88  Matrix3 matrix() const;
89 
91  Vector3 epipolarLine(const Point2& p, OptionalJacobian<3, 7> H = {});
92 
96  void print(const std::string& s = "") const;
97 
100  bool equals(const FundamentalMatrix& other, double tol = 1e-9) const;
102 
105  inline constexpr static auto dimension = 7; // 3 for U, 1 for s, 3 for V
106  inline static size_t Dim() { return dimension; }
107  inline size_t dim() const { return dimension; }
108 
110  Vector localCoordinates(const FundamentalMatrix& F) const;
111 
113  FundamentalMatrix retract(const Vector& delta) const;
115  private:
117  FundamentalMatrix(const Rot3& U, double s, const Rot3& V)
118  : U_(U), s_(s), V_(V) {}
119 
121  void initialize(Matrix3 U, double s, Matrix3 V);
122 };
123 
132 class GTSAM_EXPORT SimpleFundamentalMatrix {
133  private:
135  double fa_;
136  double fb_;
139 
141  Matrix3 Ka() const;
142 
144  Matrix3 Kb() const;
145 
146  public:
149  : E_(), fa_(1.0), fb_(1.0), ca_(0.0, 0.0), cb_(0.0, 0.0) {}
150 
160  double fa, double fb, const Point2& ca,
161  const Point2& cb)
162  : E_(E), fa_(fa), fb_(fb), ca_(ca), cb_(cb) {}
163 
166  Matrix3 matrix() const;
167 
169  Vector3 epipolarLine(const Point2& p, OptionalJacobian<3, 7> H = {});
170 
174  void print(const std::string& s = "") const;
175 
177  bool equals(const SimpleFundamentalMatrix& other, double tol = 1e-9) const;
179 
182  inline constexpr static auto dimension = 7; // 5 for E, 1 for fa, 1 for fb
183  inline static size_t Dim() { return dimension; }
184  inline size_t dim() const { return dimension; }
185 
187  Vector localCoordinates(const SimpleFundamentalMatrix& F) const;
188 
192 };
193 
200 GTSAM_EXPORT Point2 EpipolarTransfer(const Matrix3& Fca, const Point2& pa,
201  const Matrix3& Fcb, const Point2& pb);
202 
205 template <typename F>
206 struct TripleF {
208 
210  Point2 transferToA(const Point2& pb, const Point2& pc) {
211  return EpipolarTransfer(Fab.matrix(), pb, Fca.matrix().transpose(), pc);
212  }
213 
215  Point2 transferToB(const Point2& pa, const Point2& pc) {
216  return EpipolarTransfer(Fab.matrix().transpose(), pa, Fbc.matrix(), pc);
217  }
218 
220  Point2 transferToC(const Point2& pa, const Point2& pb) {
221  return EpipolarTransfer(Fca.matrix(), pa, Fbc.matrix().transpose(), pb);
222  }
223 };
224 
225 template <>
227  : public internal::Manifold<FundamentalMatrix> {};
228 
229 template <>
231  : public internal::Manifold<SimpleFundamentalMatrix> {};
232 
233 } // namespace gtsam
gtsam::SimpleFundamentalMatrix::fa_
double fa_
Focal length for left camera.
Definition: FundamentalMatrix.h:135
gtsam::FundamentalMatrix::s_
double s_
Scalar parameter for S.
Definition: FundamentalMatrix.h:32
H
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
Definition: gnuplot_common_settings.hh:74
EssentialMatrix.h
inverse
const EIGEN_DEVICE_FUNC InverseReturnType inverse() const
Definition: ArrayCwiseUnaryOps.h:411
gtsam::SimpleFundamentalMatrix::Dim
static size_t Dim()
Definition: FundamentalMatrix.h:183
gtsam::TripleF::transferToC
Point2 transferToC(const Point2 &pa, const Point2 &pb)
Transfers a point from cameras a,b to camera c.
Definition: FundamentalMatrix.h:220
gtsam::FundamentalMatrix::U_
Rot3 U_
Left rotation.
Definition: FundamentalMatrix.h:31
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::TripleF::Fbc
F Fbc
Definition: FundamentalMatrix.h:207
gtsam::SimpleFundamentalMatrix::ca_
Point2 ca_
Principal point for left camera.
Definition: FundamentalMatrix.h:137
gtsam::SimpleFundamentalMatrix::SimpleFundamentalMatrix
SimpleFundamentalMatrix(const EssentialMatrix &E, double fa, double fb, const Point2 &ca, const Point2 &cb)
Construct from essential matrix and focal lengths.
Definition: FundamentalMatrix.h:159
gtsam::utils.numerical_derivative.retract
def retract(a, np.ndarray xi)
Definition: numerical_derivative.py:44
gtsam::FundamentalMatrix::FundamentalMatrix
FundamentalMatrix(const Rot3 &U, double s, const Rot3 &V)
Private constructor for internal use.
Definition: FundamentalMatrix.h:117
gtsam::SimpleFundamentalMatrix::cb_
Point2 cb_
Principal point for right camera.
Definition: FundamentalMatrix.h:138
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
gtsam::internal::Manifold
Both ManifoldTraits and Testable.
Definition: Manifold.h:117
gtsam::EpipolarTransfer
Point2 EpipolarTransfer(const Matrix3 &Fca, const Point2 &pa, const Matrix3 &Fcb, const Point2 &pb)
Transfer projections from cameras a and b to camera c.
Definition: FundamentalMatrix.cpp:15
gtsam::TripleF::transferToB
Point2 transferToB(const Point2 &pa, const Point2 &pc)
Transfers a point from camera a,c to camera b.
Definition: FundamentalMatrix.h:215
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
Unit3.h
Rot3.h
3D rotation represented as a rotation matrix or quaternion
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:156
gtsam::TripleF::Fab
F Fab
Definition: FundamentalMatrix.h:207
gtsam.examples.PlanarManipulatorExample.delta
def delta(g0, g1)
Definition: PlanarManipulatorExample.py:45
gtsam::EssentialMatrix
Definition: EssentialMatrix.h:26
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::Pose3
Definition: Pose3.h:37
gtsam::SimpleFundamentalMatrix::dim
size_t dim() const
Definition: FundamentalMatrix.h:184
gtsam::SimpleFundamentalMatrix::SimpleFundamentalMatrix
SimpleFundamentalMatrix()
Default constructor.
Definition: FundamentalMatrix.h:148
OptionalJacobian.h
Special class for optional Jacobian arguments.
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
gtsam::FundamentalMatrix::dim
size_t dim() const
Definition: FundamentalMatrix.h:107
gtsam::symbol_shorthand::F
Key F(std::uint64_t j)
Definition: inference/Symbol.h:153
pc
int RealScalar int RealScalar int RealScalar * pc
Definition: level1_cplx_impl.h:119
matrix
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
Definition: gtsam/3rdparty/Eigen/blas/common.h:110
E
DiscreteKey E(5, 2)
gtsam::FundamentalMatrix::FundamentalMatrix
FundamentalMatrix(const Matrix3 &Ka, const EssentialMatrix &E, const Matrix3 &Kb)
Construct from essential matrix and calibration matrices.
Definition: FundamentalMatrix.h:69
gtsam
traits
Definition: SFMdata.h:40
gtsam::traits
Definition: Group.h:36
gtsam::SimpleFundamentalMatrix
Class for representing a simple fundamental matrix.
Definition: FundamentalMatrix.h:132
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::FundamentalMatrix::FundamentalMatrix
FundamentalMatrix(const Matrix3 &Ka, const Pose3 &aPb, const Matrix3 &Kb)
Construct from calibration matrices Ka, Kb, and pose aPb.
Definition: FundamentalMatrix.h:84
gtsam::TripleF::transferToA
Point2 transferToA(const Point2 &pb, const Point2 &pc)
Transfers a point from cameras b,c to camera a.
Definition: FundamentalMatrix.h:210
gtsam::TripleF
Definition: FundamentalMatrix.h:206
gtsam::tol
const G double tol
Definition: Group.h:79
U
@ U
Definition: testDecisionTree.cpp:342
V
MatrixXcd V
Definition: EigenSolver_EigenSolver_MatrixType.cpp:15
gtsam::FundamentalMatrix::FundamentalMatrix
FundamentalMatrix()
Default constructor.
Definition: FundamentalMatrix.h:37
gtsam::FundamentalMatrix
Represents a fundamental matrix in computer vision, which encodes the epipolar geometry between two v...
Definition: FundamentalMatrix.h:29
gtsam::lago::initialize
Values initialize(const NonlinearFactorGraph &graph, bool useOdometricPath)
Definition: lago.cpp:375
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
gtsam::SimpleFundamentalMatrix::E_
EssentialMatrix E_
Essential matrix.
Definition: FundamentalMatrix.h:134
gtsam::FundamentalMatrix::Dim
static size_t Dim()
Definition: FundamentalMatrix.h:106
gtsam::SimpleFundamentalMatrix::fb_
double fb_
Focal length for right camera.
Definition: FundamentalMatrix.h:136
gtsam::FundamentalMatrix::V_
Rot3 V_
Right rotation.
Definition: FundamentalMatrix.h:33
gtsam::TripleF::Fca
F Fca
Definition: FundamentalMatrix.h:207


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:11:33