New constructor
parent
e98acff79a
commit
9cfca976ba
|
@ -54,6 +54,22 @@ 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.
|
||||
*
|
||||
* @tparam CAL Calibration type, expected to have a matrix() method
|
||||
* @param E Essential matrix
|
||||
* @param Ka Calibration matrix for the left camera
|
||||
* @param Kb Calibration matrix for the right camera
|
||||
*/
|
||||
template <typename CAL>
|
||||
FundamentalMatrix(const CAL& Ka, const EssentialMatrix& E, const CAL& Kb)
|
||||
: FundamentalMatrix(Ka.K().transpose().inverse() * E.matrix() *
|
||||
Kb.K().inverse()) {}
|
||||
|
||||
/**
|
||||
* @brief Construct from calibration matrices Ka, Kb, and pose aPb
|
||||
*
|
||||
|
@ -67,9 +83,7 @@ class GTSAM_EXPORT FundamentalMatrix {
|
|||
*/
|
||||
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(Ka, EssentialMatrix::FromPose3(aPb), Kb) {}
|
||||
|
||||
/// Return the fundamental matrix representation
|
||||
Matrix3 matrix() const;
|
||||
|
|
|
@ -913,6 +913,8 @@ class FundamentalMatrix {
|
|||
FundamentalMatrix(const gtsam::Matrix3& F);
|
||||
|
||||
// Overloaded constructors for specific calibration types
|
||||
FundamentalMatrix(const gtsam::Cal3_S2& Ka, const gtsam::EssentialMatrix& E,
|
||||
const gtsam::Cal3_S2& Kb);
|
||||
FundamentalMatrix(const gtsam::Cal3_S2& Ka, const gtsam::Pose3& aPb,
|
||||
const gtsam::Cal3_S2& Kb);
|
||||
|
||||
|
|
Loading…
Reference in New Issue