Front-End

SLAM.FrontEndType

Front-End is responsible for tracking keypoints and computing poses for the Frames. It also decides when the system needs a new Keyframe in the map.

Parameters

  • current_frame::Frame: Current frame that is being processed. This is a shared Frame between FrontEnd, MapManager, Estimator and SlamManager.
  • motion_model::MotionModel: Motion model that is used to predict pose for the Frame before the actual pose for it was computed.
  • map_manager::MapManager: Map manager that is responsible for the creation of new Keyframes in the map.
  • params::Params: Parameters of the system.
  • current_image::Matrix{Gray{Float64}}: Current image that is processed.
  • previous_image::Matrix{Gray{Float64}}: Previous processed image.
  • current_pyramid::LKPyramid: Pre-computed pyramid that is used for optical flow tracking for the current_image.
  • previous_pyramid::LKPyramid: Pre-computed pyramid that is used for optical flow tracking for the previous_image.
source
SLAM.track!Function
track!(fe::FrontEnd, image, time)

Given an image and time at which it was taken, track keypoints in it. After tracking, decide if the system needs a new Keyframe added to the map. If it is the first image to be tracked, then Keyframe is always needed.

Returns

true if the system needs a new Keyframe, otherwise false.

source
SLAM.compute_pose!Function
compute_pose!(fe::FrontEnd)

Compute pose of a current Frame using P3P Ransac algorithm. Pose is computed from the triangulated Keypoints (MapPoints) that are visible in this frame.

Returns

true if the pose was successfully computed and applied to current Frame, otherwise false.

source
SLAM.compute_pose_5pt!Function
compute_pose_5pt!(fe::FrontEnd; min_parallax, use_motion_model)

Copmute pose for pixel correspondences using 5-point algorithm to recover essential matrix, then pose from it.

Arguments

  • min_parallax: Minimum parallax required between pixels in the current Frame and previous Keyframe to compute pose. Note, that parallax is rotation-compensated, meaning a rotation from current to previous frame is computed and applied to every pixel.
  • use_motion_model: If true, then use constant-velocity motion model to predict next pose from previous frame. Otherwise, the computed pose will be "local".

Returns

If successfull, 4x4 pose matrix, that transforms points from previous Keyframe to current Frame. Otherwise nothing.

source
SLAM.check_ready_for_init!Function
check_ready_for_init!(fe::FrontEnd)

Check if there is enough average rotation compensated parallax between current Frame and previous KeyFrame.

Additionally, compute Essential matrix using 5-point Ransac algorithm to filter out outliers and check if there is enough inliers to proceed.

source
SLAM.compute_parallaxFunction
compute_parallax(
    fe::FrontEnd, current_frame_id;
    compensate_rotation = true, only_2d = true, median_parallax = true)

Compute parallax in pixels between current Frame and the provided current_frame_id Frame.

Arguments

  • compensate_rotation::Bool: Compensate rotation by computing relative rotation between current Frame and previous Keyframe if true. Default is true.
  • only_2d::Bool: Consider only 2d keypoints. Default is true.
  • median_parallax::Bool: Instead of the average, compute median parallax. Default is true.
source