Fix small issues and store scaled s_

release/4.3a0
Frank Dellaert 2024-10-29 10:58:08 -07:00
parent 3e14b7194f
commit 6b96ae217f
3 changed files with 25 additions and 24 deletions

View File

@ -2,10 +2,12 @@
* @file FundamentalMatrix.cpp * @file FundamentalMatrix.cpp
* @brief FundamentalMatrix classes * @brief FundamentalMatrix classes
* @author Frank Dellaert * @author Frank Dellaert
* @date Oct 23, 2024 * @date October 2024
*/ */
#include <gtsam/base/Matrix.h>
#include <gtsam/geometry/FundamentalMatrix.h> #include <gtsam/geometry/FundamentalMatrix.h>
#include <gtsam/geometry/Point2.h>
namespace gtsam { namespace gtsam {
@ -26,8 +28,8 @@ Point2 EpipolarTransfer(const Matrix3& Fca, const Point2& pa, //
} }
//************************************************************************* //*************************************************************************
FundamentalMatrix::FundamentalMatrix(const Matrix& U, double s, FundamentalMatrix::FundamentalMatrix(const Matrix3& U, double s,
const Matrix& V) { const Matrix3& V) {
initialize(U, s, V); initialize(U, s, V);
} }
@ -57,38 +59,30 @@ FundamentalMatrix::FundamentalMatrix(const Matrix3& F) {
void FundamentalMatrix::initialize(const Matrix3& U, double s, void FundamentalMatrix::initialize(const Matrix3& U, double s,
const Matrix3& V) { const Matrix3& V) {
s_ = s; s_ = s / kScale;
sign_ = 1.0; sign_ = 1.0;
// Check if U is a reflection and its determinant is close to -1 or 1 // Check if U is a reflection and flip U and sign_ if so
double detU = U.determinant(); double detU = U.determinant(); // detU will be -1 or 1
if (std::abs(std::abs(detU) - 1.0) > 1e-9) {
throw std::invalid_argument(
"Matrix U does not have a determinant close to -1 or 1.");
}
if (detU < 0) { if (detU < 0) {
U_ = Rot3(-U); U_ = Rot3(-U);
sign_ = -sign_; // Flip sign if U is a reflection sign_ = -sign_;
} else { } else {
U_ = Rot3(U); U_ = Rot3(U);
} }
// Check if V is a reflection and its determinant is close to -1 or 1 // Same check for V
double detV = V.determinant(); 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) { if (detV < 0) {
V_ = Rot3(-V); V_ = Rot3(-V);
sign_ = -sign_; // Flip sign if V is a reflection sign_ = -sign_;
} else { } else {
V_ = Rot3(V); V_ = Rot3(V);
} }
} }
Matrix3 FundamentalMatrix::matrix() const { Matrix3 FundamentalMatrix::matrix() const {
return sign_ * U_.matrix() * Vector3(1.0, s_, 0).asDiagonal() * return sign_ * U_.matrix() * Vector3(1.0, s_ * kScale, 0).asDiagonal() *
V_.transpose().matrix(); V_.transpose().matrix();
} }

View File

@ -2,7 +2,7 @@
* @file FundamentalMatrix.h * @file FundamentalMatrix.h
* @brief FundamentalMatrix classes * @brief FundamentalMatrix classes
* @author Frank Dellaert * @author Frank Dellaert
* @date Oct 23, 2024 * @date October 2024
*/ */
#pragma once #pragma once
@ -34,9 +34,11 @@ class GTSAM_EXPORT FundamentalMatrix {
double s_; ///< Scalar parameter for S double s_; ///< Scalar parameter for S
Rot3 V_; ///< Right rotation Rot3 V_; ///< Right rotation
static constexpr double kScale = 1000; // s is stored in s_ as s/kScale
public: public:
/// Default constructor /// Default constructor
FundamentalMatrix() : U_(Rot3()), sign_(1.0), s_(1.0), V_(Rot3()) {} FundamentalMatrix() : U_(Rot3()), sign_(1.0), s_(1.0 / kScale), V_(Rot3()) {}
/** /**
* @brief Construct from U, V, and scalar s * @brief Construct from U, V, and scalar s
@ -44,7 +46,7 @@ class GTSAM_EXPORT FundamentalMatrix {
* Initializes the FundamentalMatrix From the SVD representation * Initializes the FundamentalMatrix From the SVD representation
* U*diag(1,s,0)*V^T. It will internally convert to using SO(3). * U*diag(1,s,0)*V^T. It will internally convert to using SO(3).
*/ */
FundamentalMatrix(const Matrix& U, double s, const Matrix& V); FundamentalMatrix(const Matrix3& U, double s, const Matrix3& V);
/** /**
* @brief Construct from a 3x3 matrix using SVD * @brief Construct from a 3x3 matrix using SVD
@ -60,7 +62,9 @@ class GTSAM_EXPORT FundamentalMatrix {
* @brief Construct from essential matrix and calibration matrices * @brief Construct from essential matrix and calibration matrices
* *
* Initializes the FundamentalMatrix from the given essential matrix E * Initializes the FundamentalMatrix from the given essential matrix E
* and calibration matrices Ka and Kb. * and calibration matrices Ka and Kb, using
* F = Ka^(-T) * E * Kb^(-1)
* and then calls constructor that decomposes F via SVD.
* *
* @param E Essential matrix * @param E Essential matrix
* @param Ka Calibration matrix for the left camera * @param Ka Calibration matrix for the left camera
@ -111,8 +115,8 @@ class GTSAM_EXPORT FundamentalMatrix {
/// @} /// @}
private: private:
/// Private constructor for internal use /// Private constructor for internal use
FundamentalMatrix(const Rot3& U, double sign, double s, const Rot3& V) FundamentalMatrix(const Rot3& U, double sign, double scaled_s, const Rot3& V)
: U_(U), sign_(sign), s_(s), V_(V) {} : U_(U), sign_(sign), s_(scaled_s), V_(V) {}
/// Initialize SO(3) matrices from general O(3) matrices /// Initialize SO(3) matrices from general O(3) matrices
void initialize(const Matrix3& U, double s, const Matrix3& V); void initialize(const Matrix3& U, double s, const Matrix3& V);

View File

@ -6,12 +6,15 @@
*/ */
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
#include <gtsam/base/Matrix.h>
#include <gtsam/base/Testable.h> #include <gtsam/base/Testable.h>
#include <gtsam/geometry/FundamentalMatrix.h> #include <gtsam/geometry/FundamentalMatrix.h>
#include <gtsam/geometry/Rot3.h> #include <gtsam/geometry/Rot3.h>
#include <gtsam/geometry/SimpleCamera.h> #include <gtsam/geometry/SimpleCamera.h>
#include <gtsam/geometry/Unit3.h> #include <gtsam/geometry/Unit3.h>
#include <cmath>
using namespace std::placeholders; using namespace std::placeholders;
using namespace std; using namespace std;
using namespace gtsam; using namespace gtsam;