Small API change

release/4.3a0
Frank Dellaert 2024-10-26 23:52:42 -07:00
parent 9cfca976ba
commit 36539f250a
2 changed files with 10 additions and 12 deletions

View File

@ -60,15 +60,14 @@ class GTSAM_EXPORT FundamentalMatrix {
* 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.
* *
* @tparam CAL Calibration type, expected to have a matrix() method
* @param E Essential matrix * @param E Essential matrix
* @param Ka Calibration matrix for the left camera * @param Ka Calibration matrix for the left camera
* @param Kb Calibration matrix for the right camera * @param Kb Calibration matrix for the right camera
*/ */
template <typename CAL> FundamentalMatrix(const Matrix3& Ka, const EssentialMatrix& E,
FundamentalMatrix(const CAL& Ka, const EssentialMatrix& E, const CAL& Kb) const Matrix3& Kb)
: FundamentalMatrix(Ka.K().transpose().inverse() * E.matrix() * : FundamentalMatrix(Ka.transpose().inverse() * E.matrix() *
Kb.K().inverse()) {} Kb.inverse()) {}
/** /**
* @brief Construct from calibration matrices Ka, Kb, and pose aPb * @brief Construct from calibration matrices Ka, Kb, and pose aPb
@ -76,13 +75,11 @@ class GTSAM_EXPORT FundamentalMatrix {
* Initializes the FundamentalMatrix 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
* @param Ka Calibration matrix for the left camera * @param Ka Calibration matrix for the left camera
* @param aPb Pose from the left to the right camera * @param aPb Pose from the left to the right camera
* @param Kb Calibration matrix for the right camera * @param Kb Calibration matrix for the right camera
*/ */
template <typename CAL> FundamentalMatrix(const Matrix3& Ka, const Pose3& aPb, const Matrix3& Kb)
FundamentalMatrix(const CAL& Ka, const Pose3& aPb, const CAL& Kb)
: FundamentalMatrix(Ka, EssentialMatrix::FromPose3(aPb), Kb) {} : FundamentalMatrix(Ka, EssentialMatrix::FromPose3(aPb), Kb) {}
/// Return the fundamental matrix representation /// Return the fundamental matrix representation

View File

@ -913,10 +913,10 @@ class FundamentalMatrix {
FundamentalMatrix(const gtsam::Matrix3& F); FundamentalMatrix(const gtsam::Matrix3& F);
// Overloaded constructors for specific calibration types // Overloaded constructors for specific calibration types
FundamentalMatrix(const gtsam::Cal3_S2& Ka, const gtsam::EssentialMatrix& E, FundamentalMatrix(const gtsam::Matrix3& Ka, const gtsam::EssentialMatrix& E,
const gtsam::Cal3_S2& Kb); const gtsam::Matrix3& Kb);
FundamentalMatrix(const gtsam::Cal3_S2& Ka, const gtsam::Pose3& aPb, FundamentalMatrix(const gtsam::Matrix3& Ka, const gtsam::Pose3& aPb,
const gtsam::Cal3_S2& Kb); const gtsam::Matrix3& Kb);
// Methods // Methods
gtsam::Matrix3 matrix() const; gtsam::Matrix3 matrix() const;
@ -1066,6 +1066,7 @@ typedef gtsam::PinholeCamera<gtsam::Cal3_S2> PinholeCameraCal3_S2;
typedef gtsam::PinholeCamera<gtsam::Cal3DS2> PinholeCameraCal3DS2; typedef gtsam::PinholeCamera<gtsam::Cal3DS2> PinholeCameraCal3DS2;
typedef gtsam::PinholeCamera<gtsam::Cal3Unified> PinholeCameraCal3Unified; typedef gtsam::PinholeCamera<gtsam::Cal3Unified> PinholeCameraCal3Unified;
typedef gtsam::PinholeCamera<gtsam::Cal3Bundler> PinholeCameraCal3Bundler; typedef gtsam::PinholeCamera<gtsam::Cal3Bundler> PinholeCameraCal3Bundler;
typedef gtsam::PinholeCamera<gtsam::Cal3f> PinholeCameraCal3f;
typedef gtsam::PinholeCamera<gtsam::Cal3Fisheye> PinholeCameraCal3Fisheye; typedef gtsam::PinholeCamera<gtsam::Cal3Fisheye> PinholeCameraCal3Fisheye;
#include <gtsam/geometry/PinholePose.h> #include <gtsam/geometry/PinholePose.h>