Use FundamentalMatrix now

release/4.3a0
Frank Dellaert 2024-10-24 17:36:53 -07:00
parent ca199f9c08
commit 19c75cb95c
2 changed files with 6 additions and 6 deletions

View File

@ -47,8 +47,8 @@ int main(int argc, char* argv[]) {
vector<Pose3> poses = posesOnCircle(4, 30); vector<Pose3> poses = posesOnCircle(4, 30);
// Calculate ground truth fundamental matrices, 1 and 2 poses apart // Calculate ground truth fundamental matrices, 1 and 2 poses apart
auto F1 = GeneralFundamentalMatrix(K, poses[0].between(poses[1]), K); auto F1 = FundamentalMatrix(K, poses[0].between(poses[1]), K);
auto F2 = GeneralFundamentalMatrix(K, poses[0].between(poses[2]), K); auto F2 = FundamentalMatrix(K, poses[0].between(poses[2]), K);
// Simulate measurements from each camera pose // Simulate measurements from each camera pose
std::array<std::array<Point2, 8>, 4> p; std::array<std::array<Point2, 8>, 4> p;
@ -67,7 +67,7 @@ int main(int argc, char* argv[]) {
// in a triplet, we add three binary factors for sparsity during optimization. // in a triplet, we add three binary factors for sparsity during optimization.
// In this version, we only include triplets between 3 successive cameras. // In this version, we only include triplets between 3 successive cameras.
NonlinearFactorGraph graph; NonlinearFactorGraph graph;
using Factor = TransferFactor<GeneralFundamentalMatrix>; using Factor = TransferFactor<FundamentalMatrix>;
for (size_t a = 0; a < 4; ++a) { for (size_t a = 0; a < 4; ++a) {
size_t b = (a + 1) % 4; // Next camera size_t b = (a + 1) % 4; // Next camera
size_t c = (a + 2) % 4; // Camera after next size_t c = (a + 2) % 4; // Camera after next

View File

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