8 #ifndef META_OCEAN_GEOMETRY_HOMOGRAPHY_H
9 #define META_OCEAN_GEOMETRY_HOMOGRAPHY_H
132 static inline bool homographyMatrix(
const Vector2* leftPoints,
const Vector2* rightPoints,
const size_t correspondences,
SquareMatrix3& right_H_left,
const bool useSVD =
true);
193 static inline bool homographyMatrixLinearWithOptimizations(
const Vector2* leftPoints,
const Vector2* rightPoints,
const size_t correspondences,
SquareMatrix3& right_H_left);
333 template <
typename T>
341 template <
typename T>
351 template <
typename T>
366 static bool isHomographyPlausible(
const unsigned int leftImageWidth,
const unsigned int leftImageHeight,
const unsigned int rightImageWidth,
const unsigned int rightImageHeight,
const SquareMatrix3& homography);
434 template <
typename T>
440 ocean_assert(leftPoints && rightPoints && correspondences >= 4);
454 ocean_assert(leftPoints && rightPoints && correspondences >= 4);
459 template <
typename T>
465 template <
typename T>
471 template <
typename T>
479 const T invScaleLeft = T(1) / scaleLeft;
483 scaledHomography[0] = homography[0] * scaleRight * invScaleLeft;
484 scaledHomography[1] = homography[1] * scaleRight * invScaleLeft;
485 scaledHomography[2] = homography[2] * invScaleLeft;
487 scaledHomography[3] = homography[3] * scaleRight * invScaleLeft;
488 scaledHomography[4] = homography[4] * scaleRight * invScaleLeft;
489 scaledHomography[5] = homography[5] * invScaleLeft;
491 scaledHomography[6] = homography[6] * scaleRight;
492 scaledHomography[7] = homography[7] * scaleRight;
493 scaledHomography[8] = homography[8];
501 return scaledHomography;
504 template <
typename T>
509 return homographyForPoints.
transposed().inverted();
This class implements the abstract base class for all AnyCamera objects.
Definition: AnyCamera.h:130
This class implements functions necessary for computations with homographies.
Definition: Homography.h:33
static bool extrinsicMatrix(const SquareMatrix3 &intrinsic, const SquareMatrix3 &homography, HomogenousMatrix4 &world_T_camera)
Calculates the extrinsic camera matrix for a given intrinsic camera matrix and a corresponding homogr...
static bool factorizeHomographyMatrix(const SquareMatrix3 &right_H_left, const PinholeCamera &leftCamera, const PinholeCamera &rightCamera, const ImagePoint *leftImagePoints, const ImagePoint *rightImagePoints, const size_t correspondences, HomogenousMatrix4 world_T_rightCameras[2], Vector3 normals[2])
Factorizes a planar homography into translation and rotation of the camera.
static void normalizeHomography(SquareMatrixT3< T > &homography)
Normalizes a given homography forcing a 1 in the lower right matrix corner.
Definition: Homography.h:466
static bool homotheticMatrix(const ImagePoint *leftPoints, const ImagePoint *rightPoints, const size_t correspondences, SquareMatrix3 &right_H_left)
Calculates the homothetic transformation (3DOF - translation, scale) between two sets of image points...
static SquareMatrix3 toFinestHomography(const SquareMatrix3 &coarseHomography, const unsigned int sourceLayer)
Converts a given homography determined for a coarser pyramid layer to a homography matching with the ...
static SquareMatrix3 homographyMatrix(const PinholeCamera &pinholeCamera, const HomogenousMatrix4 &pose, const Vector3 &patternObjectPointTopLeft, const Vector3 &patternObjectPointBottomLeft, const Vector3 &patternObjectPointTopRight, const unsigned int patternWidth, const unsigned int patternHeight)
Calculates the homography that transforms points defined in a (planar) pattern image to points define...
static bool distortionParameters(const ConstIndexedAccessor< HomogenousMatrix4 > &extrinsics, const SquareMatrix3 &intrinsic, const ConstIndexedAccessor< Vectors3 > &objectPointGroups, const ConstIndexedAccessor< Vectors2 > &imagePointGroups, Scalar &distortion2, Scalar &distortion4)
Calculates the first two radial distortion parameter.
static bool homographyMatrixLinear(const Vector2 *leftPoints, const Vector2 *rightPoints, const size_t correspondences, SquareMatrix3 &right_H_left, unsigned int optimizationIterations)
Calculates the homography (8DOF - translation, rotation, scale, aspect ratio, shear,...
static bool homographyMatrixLinearWithOptimizations(const Vector2 *leftPoints, const Vector2 *rightPoints, const size_t correspondences, SquareMatrix3 &right_H_left)
Calculates the homography (8DOF - translation, rotation, scale, aspect ratio, shear,...
Definition: Homography.h:452
static SquareMatrix3 factorizeHomographyMatrix(const SquareMatrix3 &homography, const PinholeCamera &leftCamera, const PinholeCamera &rightCamera)
Factorizes a homography which contains only a rotational part into the corresponding rotation (of the...
static SquareMatrix3 homographyMatrix(const Quaternion &left_T_right, const PinholeCamera &leftCamera, const PinholeCamera &rightCamera)
Deprecated.
static SquareMatrix3 homographyMatrix(const Quaternion &left_T_right, const AnyCamera &leftCamera, const AnyCamera &rightCamera)
Calculates the homography between two images transforming the projected planar object points between ...
static bool intrinsicMatrix(const SquareMatrix3 *homographies, const size_t number, SquareMatrix3 &intrinsic)
Calculates the intrinsic camera matrix for a set of given homographies transforming 3D object points ...
static bool homographyMatrixPlaneXY(const ImagePoint *objectPoints, const ImagePoint *imagePoints, const size_t correspondences, SquareMatrix3 &homography)
Calculates the homography for given 3D object points lying on the Z == 0 plane and 2D image points.
static SquareMatrix3 homographyMatrix(const HomogenousMatrix4 &poseLeft, const HomogenousMatrix4 &poseRight, const PinholeCamera &leftCamera, const PinholeCamera &rightCamera, const Plane3 &plane)
Calculates the homography between two images transforming the projected planar object points between ...
static SquareMatrix3 homographyMatrix(const Quaternion &world_R_left, const Quaternion &world_R_right, const PinholeCamera &leftCamera, const PinholeCamera &rightCamera)
Calculates the homography between two images transforming the projected planar object points between ...
static bool homographyMatrixFromPointsAndLinesSVD(const Vector2 *leftPoints, const Vector2 *rightPoints, const size_t pointCorrespondences, const Line2 *leftLines, const Line2 *rightLines, const size_t lineCorrespondences, SquareMatrix3 &right_H_left)
Calculates the homography (8DOF - translation, rotation, scale, aspect ratio, shear,...
static SquareMatrix3 toCoarseHomography(const SquareMatrix3 &finestHomography, const unsigned int targetLayer)
Converts a given homography determined for the finest pyramid layer to a homography matching with a c...
static SquareMatrix3 homographyMatrix(const HomogenousMatrix4 &world_T_rightCamera, const PinholeCamera &leftCamera, const PinholeCamera &rightCamera, const Plane3 &plane)
Calculates the homography between two images transforming the projected planar object points between ...
static bool homographyMatrixSVD(const Vector2 *leftPoints, const Vector2 *rightPoints, const size_t correspondences, SquareMatrix3 &right_H_left)
Calculates the homography (8DOF - translation, rotation, scale, aspect ratio, shear,...
static bool homographyMatrixLinearWithoutOptimations(const Vector2 *leftPoints, const Vector2 *rightPoints, const size_t correspondences, SquareMatrix3 &right_H_left)
Calculates the homography (8DOF - translation, rotation, scale, aspect ratio, shear,...
static SquareMatrixT3< T > scaleHomography(const SquareMatrixT3< T > &homography, const T &scaleLeft, const T &scaleRight)
Scales a given homography so that it fits to an individually scaled input image and an individually s...
Definition: Homography.h:472
static SquareMatrixT3< T > normalizedHomography(const SquareMatrixT3< T > &homography)
Normalizes a given homography forcing a 1 in the lower right matrix corner.
Definition: Homography.h:460
static bool homographyMatrixPlaneXY(const ObjectPoint *objectPoints, const ImagePoint *imagePoints, const size_t correspondences, SquareMatrix3 &homography)
Calculates the homography for given 3D object points lying on the Z == 0 plane and corresponding 2D i...
static bool affineMatrix(const ImagePoint *leftPoints, const ImagePoint *rightPoints, const size_t correspondences, SquareMatrix3 &right_A_left)
Calculates the affine transformation (6DOF - translation, rotation, scale, aspect ratio,...
static SquareMatrixT3< T > homographyForLines(const SquareMatrixT3< T > &homographyForPoints)
Returns the homography transforming lines from one image to another image based on a homography trans...
Definition: Homography.h:505
static bool factorizeHomographyMatrix(const SquareMatrix3 &right_H_left, const HomogenousMatrix4 &world_T_leftCamera, const PinholeCamera &leftCamera, const PinholeCamera &rightCamera, const ImagePoint *leftImagePoints, const ImagePoint *rightImagePoints, const size_t correspondences, HomogenousMatrix4 world_T_rightCameras[2], Vector3 normals[2])
Factorizes a planar homography into translation and rotation of the camera.
static bool isHomographyPlausible(const unsigned int leftImageWidth, const unsigned int leftImageHeight, const unsigned int rightImageWidth, const unsigned int rightImageHeight, const SquareMatrix3 &homography)
Returns whether a given homography represents a plausible transformation.
static bool similarityMatrix(const ImagePoint *leftPoints, const ImagePoint *rightPoints, const size_t correspondences, SquareMatrix3 &right_S_left)
Calculates the similarity transformation (4DOF - translation, rotation, scale) between two images tra...
static void normalizeTransformation(SquareMatrixT3< T > &transformation)
Normalizes a given 3x3 transformation matrix which is defined up to a scale factor forcing a 1 in the...
Definition: Normalization.h:75
static SquareMatrixT3< T > normalizedTransformation(const SquareMatrixT3< T > &transformation)
Normalizes a given 3x3 transformation matrix which is defined up to a scale factor forcing a 1 in the...
Definition: Normalization.h:58
This class implements an infinite line in 2D space.
Definition: Line2.h:83
This class provides basic numeric functionalities.
Definition: Numeric.h:57
bool isEqual(const SquareMatrixT3< T > &matrix, const T eps=NumericT< T >::eps()) const
Returns whether two matrices are almost identical up to a specified epsilon.
Definition: SquareMatrix3.h:1386
SquareMatrixT3< T > transposed() const
Returns the transposed of this matrix.
Definition: SquareMatrix3.h:1144
bool isHomography() const
Returns true if this matrix is perspective transform/homography.
Definition: SquareMatrix3.h:1359
SquareMatrixT3< T > inverted() const
Returns the inverted matrix of this matrix.
Definition: SquareMatrix3.h:1176
bool isSingular() const
Returns whether this matrix is singular (and thus cannot be inverted).
Definition: SquareMatrix3.h:1341
float Scalar
Definition of a scalar type.
Definition: Math.h:128
The namespace covering the entire Ocean framework.
Definition: Accessor.h:15