Front-End
SLAM.FrontEnd
— TypeFront-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 thecurrent_image
.previous_pyramid::LKPyramid
: Pre-computed pyramid that is used for optical flow tracking for theprevious_image
.
SLAM.track!
— Functiontrack!(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
.
SLAM.klt_tracking!
— Functionklt_tracking!(fe::FrontEnd)
Track keypoints from previous frame to current frame.
SLAM.compute_pose!
— Functioncompute_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
.
SLAM.compute_pose_5pt!
— Functioncompute_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
: Iftrue
, 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
.
SLAM.check_ready_for_init!
— Functioncheck_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.
SLAM.check_new_kf_required
— Functioncheck_new_kf_required(fe::FrontEnd)
Check if we need to insert a new KeyFrame into the Map.
SLAM.compute_parallax
— Functioncompute_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 iftrue
. Default istrue
.only_2d::Bool
: Consider only 2d keypoints. Default istrue
.median_parallax::Bool
: Instead of the average, compute median parallax. Default istrue
.
SLAM.reset_frame!
— Methodreset_frame!(fe::FrontEnd)
Reset current Frame in Front-End.
SLAM.reset!
— Methodreset!(fe::FrontEnd)
Reset Front-End.