Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

F wrapper and bugfix #1888

Merged
merged 14 commits into from
Oct 31, 2024
2 changes: 1 addition & 1 deletion examples/SFMdata.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ std::vector<Point3> createPoints() {

/**
* Create a set of ground-truth poses
* Default values give a circular trajectory, radius 30 at pi/4 intervals,
* Default values give a circular trajectory, radius 30 at pi/4 intervals,
* always facing the circle center
*/
std::vector<Pose3> createPoses(
Expand Down
8 changes: 4 additions & 4 deletions examples/ViewGraphExample.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ using namespace gtsam;
/* ************************************************************************* */
int main(int argc, char* argv[]) {
// Define the camera calibration parameters
Cal3_S2 K(50.0, 50.0, 0.0, 50.0, 50.0);
Cal3_S2 cal(50.0, 50.0, 0.0, 50.0, 50.0);

// Create the set of 8 ground-truth landmarks
vector<Point3> points = createPoints();
Expand All @@ -47,13 +47,13 @@ int main(int argc, char* argv[]) {
vector<Pose3> poses = posesOnCircle(4, 30);

// Calculate ground truth fundamental matrices, 1 and 2 poses apart
auto F1 = FundamentalMatrix(K, poses[0].between(poses[1]), K);
auto F2 = FundamentalMatrix(K, poses[0].between(poses[2]), K);
auto F1 = FundamentalMatrix(cal.K(), poses[0].between(poses[1]), cal.K());
auto F2 = FundamentalMatrix(cal.K(), poses[0].between(poses[2]), cal.K());

// Simulate measurements from each camera pose
std::array<std::array<Point2, 8>, 4> p;
for (size_t i = 0; i < 4; ++i) {
PinholeCamera<Cal3_S2> camera(poses[i], K);
PinholeCamera<Cal3_S2> camera(poses[i], cal);
for (size_t j = 0; j < 8; ++j) {
p[i][j] = camera.project(points[j]);
}
Expand Down
57 changes: 39 additions & 18 deletions gtsam/geometry/FundamentalMatrix.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,11 @@ Point2 EpipolarTransfer(const Matrix3& Fca, const Point2& pa, //
}

//*************************************************************************
FundamentalMatrix::FundamentalMatrix(const Matrix& U, double s,
const Matrix& V) {
initialize(U, s, V);
}

FundamentalMatrix::FundamentalMatrix(const Matrix3& F) {
// Perform SVD
Eigen::JacobiSVD<Matrix3> svd(F, Eigen::ComputeFullU | Eigen::ComputeFullV);
Expand All @@ -47,28 +52,44 @@ FundamentalMatrix::FundamentalMatrix(const Matrix3& F) {
"The input matrix does not represent a valid fundamental matrix.");
}

// Ensure the second singular value is recorded as s
s_ = singularValues(1);
initialize(U, singularValues(1), V);
}

// Check if U is a reflection
if (U.determinant() < 0) {
U = -U;
s_ = -s_; // Change sign of scalar if U is a reflection
}
void FundamentalMatrix::initialize(const Matrix3& U, double s,
const Matrix3& V) {
s_ = s;
sign_ = 1.0;

// Check if V is a reflection
if (V.determinant() < 0) {
V = -V;
s_ = -s_; // Change sign of scalar if U is a reflection
// Check if U is a reflection and its determinant is close to -1 or 1
double detU = U.determinant();
if (std::abs(std::abs(detU) - 1.0) > 1e-9) {
dellaert marked this conversation as resolved.
Show resolved Hide resolved
throw std::invalid_argument(
"Matrix U does not have a determinant close to -1 or 1.");
}
if (detU < 0) {
U_ = Rot3(-U);
sign_ = -sign_; // Flip sign if U is a reflection
} else {
U_ = Rot3(U);
}

// Assign the rotations
U_ = Rot3(U);
V_ = Rot3(V);
// Check if V is a reflection and its determinant is close to -1 or 1
double detV = V.determinant();
if (std::abs(std::abs(detV) - 1.0) > 1e-9) {
throw std::invalid_argument(
"Matrix V does not have a determinant close to -1 or 1.");
}
if (detV < 0) {
V_ = Rot3(-V);
sign_ = -sign_; // Flip sign if V is a reflection
} else {
V_ = Rot3(V);
}
}

Matrix3 FundamentalMatrix::matrix() const {
return U_.matrix() * Vector3(1, s_, 0).asDiagonal() * V_.transpose().matrix();
return sign_ * U_.matrix() * Vector3(1.0, s_, 0).asDiagonal() *
V_.transpose().matrix();
}

void FundamentalMatrix::print(const std::string& s) const {
Expand All @@ -77,8 +98,8 @@ void FundamentalMatrix::print(const std::string& s) const {

bool FundamentalMatrix::equals(const FundamentalMatrix& other,
double tol) const {
return U_.equals(other.U_, tol) && std::abs(s_ - other.s_) < tol &&
V_.equals(other.V_, tol);
return U_.equals(other.U_, tol) && sign_ == other.sign_ &&
std::abs(s_ - other.s_) < tol && V_.equals(other.V_, tol);
}

Vector FundamentalMatrix::localCoordinates(const FundamentalMatrix& F) const {
Expand All @@ -93,7 +114,7 @@ FundamentalMatrix FundamentalMatrix::retract(const Vector& delta) const {
Rot3 newU = U_.retract(delta.head<3>());
double newS = s_ + delta(3); // Update scalar
Rot3 newV = V_.retract(delta.tail<3>());
return FundamentalMatrix(newU, newS, newV);
return FundamentalMatrix(newU, sign_, newS, newV);
}

//*************************************************************************
Expand Down
64 changes: 42 additions & 22 deletions gtsam/geometry/FundamentalMatrix.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,34 +15,36 @@ namespace gtsam {

/**
* @class FundamentalMatrix
* @brief Represents a general fundamental matrix.
* @brief Represents a fundamental matrix in computer vision, which encodes the
* epipolar geometry between two views.
*
* This class represents a general fundamental matrix, which is a 3x3 matrix
* that describes the relationship between two images. It is parameterized by a
* left rotation U, a scalar s, and a right rotation V.
* The FundamentalMatrix class encapsulates the fundamental matrix, which
* relates corresponding points in stereo images. It is parameterized by two
* rotation matrices (U and V), a scalar parameter (s), and a sign.
* Using these values, the fundamental matrix is represented as
*
* F = sign * U * diag(1, s, 0) * V^T
*
* We need the `sign` because we use SO(3) for U and V, not O(3).
*/
class GTSAM_EXPORT FundamentalMatrix {
private:
Rot3 U_; ///< Left rotation
double s_; ///< Scalar parameter for S
Rot3 V_; ///< Right rotation
Rot3 U_; ///< Left rotation
double sign_; ///< Whether to flip the sign or not
double s_; ///< Scalar parameter for S
Rot3 V_; ///< Right rotation

public:
/// Default constructor
FundamentalMatrix() : U_(Rot3()), s_(1.0), V_(Rot3()) {}
FundamentalMatrix() : U_(Rot3()), sign_(1.0), s_(1.0), V_(Rot3()) {}

/**
* @brief Construct from U, V, and scalar s
*
* Initializes the FundamentalMatrix with the given left rotation U,
* scalar s, and right rotation V.
*
* @param U Left rotation matrix
* @param s Scalar parameter for the fundamental matrix
* @param V Right rotation matrix
* Initializes the FundamentalMatrix From the SVD representation
* U*diag(1,s,0)*V^T. It will internally convert to using SO(3).
*/
FundamentalMatrix(const Rot3& U, double s, const Rot3& V)
: U_(U), s_(s), V_(V) {}
FundamentalMatrix(const Matrix& U, double s, const Matrix& V);
dellaert marked this conversation as resolved.
Show resolved Hide resolved

/**
* @brief Construct from a 3x3 matrix using SVD
Expand All @@ -54,22 +56,33 @@ class GTSAM_EXPORT FundamentalMatrix {
*/
FundamentalMatrix(const Matrix3& F);

/**
* @brief Construct from essential matrix and calibration matrices
*
* Initializes the FundamentalMatrix from the given essential matrix E
* and calibration matrices Ka and Kb.
dellaert marked this conversation as resolved.
Show resolved Hide resolved
*
* @param E Essential matrix
* @param Ka Calibration matrix for the left camera
* @param Kb Calibration matrix for the right camera
*/
FundamentalMatrix(const Matrix3& Ka, const EssentialMatrix& E,
const Matrix3& Kb)
: FundamentalMatrix(Ka.transpose().inverse() * E.matrix() *
Kb.inverse()) {}

/**
* @brief Construct from calibration matrices Ka, Kb, and pose aPb
*
* Initializes the FundamentalMatrix from the given calibration
* matrices Ka and Kb, and the pose aPb.
*
* @tparam CAL Calibration type, expected to have a matrix() method
* @param Ka Calibration matrix for the left camera
* @param aPb Pose from the left to the right camera
* @param Kb Calibration matrix for the right camera
*/
template <typename CAL>
FundamentalMatrix(const CAL& Ka, const Pose3& aPb, const CAL& Kb)
: FundamentalMatrix(Ka.K().transpose().inverse() *
EssentialMatrix::FromPose3(aPb).matrix() *
Kb.K().inverse()) {}
FundamentalMatrix(const Matrix3& Ka, const Pose3& aPb, const Matrix3& Kb)
: FundamentalMatrix(Ka, EssentialMatrix::FromPose3(aPb), Kb) {}

/// Return the fundamental matrix representation
Matrix3 matrix() const;
Expand All @@ -96,6 +109,13 @@ class GTSAM_EXPORT FundamentalMatrix {
/// Retract the given vector to get a new FundamentalMatrix
FundamentalMatrix retract(const Vector& delta) const;
/// @}
private:
/// Private constructor for internal use
FundamentalMatrix(const Rot3& U, double sign, double s, const Rot3& V)
: U_(U), sign_(sign), s_(s), V_(V) {}

/// Initialize SO(3) matrices from general O(3) matrices
void initialize(const Matrix3& U, double s, const Matrix3& V);
};

/**
Expand Down
61 changes: 58 additions & 3 deletions gtsam/geometry/geometry.i
Original file line number Diff line number Diff line change
Expand Up @@ -578,6 +578,8 @@ class Unit3 {
// Standard Constructors
Unit3();
Unit3(const gtsam::Point3& pose);
Unit3(double x, double y, double z);
Unit3(const gtsam::Point2& p, double f);

// Testable
void print(string s = "") const;
Expand Down Expand Up @@ -620,10 +622,10 @@ class EssentialMatrix {
EssentialMatrix(const gtsam::Rot3& aRb, const gtsam::Unit3& aTb);

// Constructors from Pose3
gtsam::EssentialMatrix FromPose3(const gtsam::Pose3& _1P2_);
static gtsam::EssentialMatrix FromPose3(const gtsam::Pose3& _1P2_);

gtsam::EssentialMatrix FromPose3(const gtsam::Pose3& _1P2_,
Eigen::Ref<Eigen::MatrixXd> H);
static gtsam::EssentialMatrix FromPose3(const gtsam::Pose3& _1P2_,
Eigen::Ref<Eigen::MatrixXd> H);

// Testable
void print(string s = "") const;
Expand Down Expand Up @@ -903,6 +905,59 @@ class Cal3Bundler {
void serialize() const;
};

#include <gtsam/geometry/FundamentalMatrix.h>

// FundamentalMatrix class
class FundamentalMatrix {
// Constructors
FundamentalMatrix();
FundamentalMatrix(const gtsam::Matrix3& U, double s, const gtsam::Matrix3& V);
FundamentalMatrix(const gtsam::Matrix3& F);

// Overloaded constructors for specific calibration types
FundamentalMatrix(const gtsam::Matrix3& Ka, const gtsam::EssentialMatrix& E,
const gtsam::Matrix3& Kb);
FundamentalMatrix(const gtsam::Matrix3& Ka, const gtsam::Pose3& aPb,
const gtsam::Matrix3& Kb);

// Methods
gtsam::Matrix3 matrix() const;

// Testable
void print(const std::string& s = "") const;
bool equals(const gtsam::FundamentalMatrix& other, double tol = 1e-9) const;

// Manifold
static size_t Dim();
size_t dim() const;
gtsam::Vector localCoordinates(const gtsam::FundamentalMatrix& F) const;
gtsam::FundamentalMatrix retract(const gtsam::Vector& delta) const;
};

// SimpleFundamentalMatrix class
class SimpleFundamentalMatrix {
// Constructors
SimpleFundamentalMatrix();
SimpleFundamentalMatrix(const gtsam::EssentialMatrix& E, double fa, double fb,
const gtsam::Point2& ca, const gtsam::Point2& cb);

// Methods
gtsam::Matrix3 matrix() const;

// Testable
void print(const std::string& s = "") const;
bool equals(const gtsam::SimpleFundamentalMatrix& other, double tol = 1e-9) const;

// Manifold
static size_t Dim();
size_t dim() const;
gtsam::Vector localCoordinates(const gtsam::SimpleFundamentalMatrix& F) const;
gtsam::SimpleFundamentalMatrix retract(const gtsam::Vector& delta) const;
};

gtsam::Point2 EpipolarTransfer(const gtsam::Matrix3& Fca, const gtsam::Point2& pa,
const gtsam::Matrix3& Fcb, const gtsam::Point2& pb);

#include <gtsam/geometry/CalibratedCamera.h>
class CalibratedCamera {
// Standard Constructors and Named Constructors
Expand Down
27 changes: 22 additions & 5 deletions gtsam/geometry/tests/testFundamentalMatrix.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,21 +24,38 @@ GTSAM_CONCEPT_MANIFOLD_INST(FundamentalMatrix)
Rot3 trueU = Rot3::Yaw(M_PI_2);
Rot3 trueV = Rot3::Yaw(M_PI_4);
double trueS = 0.5;
FundamentalMatrix trueF(trueU, trueS, trueV);
FundamentalMatrix trueF(trueU.matrix(), trueS, trueV.matrix());

//*************************************************************************
TEST(FundamentalMatrix, localCoordinates) {
TEST(FundamentalMatrix, LocalCoordinates) {
Vector expected = Z_7x1; // Assuming 7 dimensions for U, V, and s
Vector actual = trueF.localCoordinates(trueF);
EXPECT(assert_equal(expected, actual, 1e-8));
}

//*************************************************************************
TEST(FundamentalMatrix, retract) {
TEST(FundamentalMatrix, Retract) {
FundamentalMatrix actual = trueF.retract(Z_7x1);
EXPECT(assert_equal(trueF, actual));
}

//*************************************************************************
// Test conversion from F matrices, including non-rotations
TEST(FundamentalMatrix, Conversion) {
Matrix3 U = trueU.matrix();
Matrix3 V = trueV.matrix();
std::vector<FundamentalMatrix> Fs = {
FundamentalMatrix(U, trueS, V), FundamentalMatrix(U, trueS, -V),
FundamentalMatrix(-U, trueS, V), FundamentalMatrix(-U, trueS, -V)};

for (const auto& trueF : Fs) {
const Matrix3 F = trueF.matrix();
FundamentalMatrix actual(F);
// We check the matrices as the underlying representation is not unique
CHECK(assert_equal(F, actual.matrix()));
}
}

//*************************************************************************
TEST(FundamentalMatrix, RoundTrip) {
Vector7 d;
Expand All @@ -61,14 +78,14 @@ TEST(SimpleStereo, Conversion) {
}

//*************************************************************************
TEST(SimpleStereo, localCoordinates) {
TEST(SimpleStereo, LocalCoordinates) {
Vector expected = Z_7x1;
Vector actual = stereoF.localCoordinates(stereoF);
EXPECT(assert_equal(expected, actual, 1e-8));
}

//*************************************************************************
TEST(SimpleStereo, retract) {
TEST(SimpleStereo, Retract) {
SimpleFundamentalMatrix actual = stereoF.retract(Z_9x1);
EXPECT(assert_equal(stereoF, actual));
}
Expand Down
3 changes: 3 additions & 0 deletions gtsam/nonlinear/nonlinear.i
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@ namespace gtsam {
#include <gtsam/geometry/Cal3_S2.h>
#include <gtsam/geometry/CalibratedCamera.h>
#include <gtsam/geometry/EssentialMatrix.h>
#include <gtsam/geometry/FundamentalMatrix.h>
#include <gtsam/geometry/PinholeCamera.h>
#include <gtsam/geometry/Point2.h>
#include <gtsam/geometry/Point3.h>
Expand Down Expand Up @@ -537,6 +538,8 @@ class ISAM2 {
template <VALUE = {gtsam::Point2, gtsam::Rot2, gtsam::Pose2, gtsam::Point3,
gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2,
gtsam::Cal3Bundler, gtsam::EssentialMatrix,
gtsam::Cal3Bundler, gtsam::FundamentalMatrix,
gtsam::Cal3Bundler, gtsam::SimpleFundamentalMatrix,
gtsam::PinholeCamera<gtsam::Cal3_S2>,
gtsam::PinholeCamera<gtsam::Cal3Bundler>,
gtsam::PinholeCamera<gtsam::Cal3Fisheye>,
Expand Down
Loading
Loading