Skip to content

Commit

Permalink
Get rid of scale
Browse files Browse the repository at this point in the history
  • Loading branch information
dellaert committed Oct 29, 2024
1 parent 6457937 commit 5a2f1f8
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 5 deletions.
4 changes: 2 additions & 2 deletions gtsam/geometry/FundamentalMatrix.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ FundamentalMatrix::FundamentalMatrix(const Matrix3& F) {

void FundamentalMatrix::initialize(const Matrix3& U, double s,
const Matrix3& V) {
s_ = s / kScale;
s_ = s;
sign_ = 1.0;

// Check if U is a reflection and flip U and sign_ if so
Expand All @@ -82,7 +82,7 @@ void FundamentalMatrix::initialize(const Matrix3& U, double s,
}

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

Expand Down
4 changes: 1 addition & 3 deletions gtsam/geometry/FundamentalMatrix.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,11 +34,9 @@ class GTSAM_EXPORT FundamentalMatrix {
double s_; ///< Scalar parameter for S
Rot3 V_; ///< Right rotation

static constexpr double kScale = 1000; // s is stored in s_ as s/kScale

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

/**
* @brief Construct from U, V, and scalar s
Expand Down

0 comments on commit 5a2f1f8

Please sign in to comment.