FivePoint algorithm

Used for computing Essential matrix and pose matrix from it.

RecoverPose.five_pointFunction
five_point(points1, points2, K1, K2; max_repr_error = 1.0)

Compute Essential matrix and recover pose from it for a given set of points. This function accepts five points, if you have more of them, consider using five_point_ransac version.

Arguments:

  • points1: Pixel coordinates of the matched points in (x, y) format in the first image.
  • points2: Pixel coordinates of the matched points in (x, y) format in the second image.
  • K1: Intrinsic matrix for the first set of points.
  • K2: Intrinsic matrix for the second set of points.
  • max_repr_error: Maximum allowed reprojection error for a point to be considered as inlier. Default is 1.0.

Returns:

n_inliers, (E, P, inliers, repr_error):

  • number of inliers
  • tuple: essential matrix, pose matrix, boolean vector of inliers, error value.
Note

Pose matrix transforms points from the first camera to the second camera.

source
RecoverPose.five_point_ransacFunction
five_point_ransac(
    points1, points2, K1, K2; max_repr_error = 1.0, ransac_kwargs...)

Compute Essential matrix and recover pose from it using RANSAC scheme.

Arguments:

  • points1: Pixel coordinates of the matched points in (x, y) format in the first image.
  • points2: Pixel coordinates of the matched points in (x, y) format in the second image.
  • K1: Intrinsic matrix for the first set of points.
  • K2: Intrinsic matrix for the second set of points.
  • max_repr_error: Maximum allowed reprojection error for a point to be considered as inlier. Default is 1.0.
  • ransac_kwargs...: Keyword arguments passed to ransac.

Returns:

n_inliers, (E, P, inliers, repr_error):

  • number of inliers
  • tuple: essential matrix, pose matrix, boolean vector of inliers, error value.
Note

Pose matrix transforms points from the first camera to the second camera.

source
RecoverPose.essential_ransacFunction
essential_ransac(pd1, pd2, focal_sum; threshold = 1.0, ransac_kwargs...)

Compute Essential matrix using the RANASC scheme.

Arguments:

  • pd1: Pixel coordinates predivided by K^-1 of the matched points in (x, y) format in the first image.
  • pd2: Pixel coordinates predivided by K^-1 of the matched points in (x, y) format in the second image.
  • focal_sum: fx + fy.
  • threshold: Maximum error for the epipolar constraint. Default is 1.0.
  • ransac_kwargs...: Keyword arguments passed to ransac.

Returns:

n_inliers, (E, inliers, repr_error):

  • number of inliers
  • tuple: essential matrix, boolean vector of inliers, error value.
source