Package boofcv.alg.sfm.d3
Class VisOdomMonoDepthPnP<T extends ImageBase<T>>
java.lang.Object
boofcv.alg.sfm.d3.VisOdomBundlePnPBase<VisOdomMonoDepthPnP.Track>
boofcv.alg.sfm.d3.VisOdomMonoDepthPnP<T>
- All Implemented Interfaces:
VerbosePrint
public class VisOdomMonoDepthPnP<T extends ImageBase<T>>
extends VisOdomBundlePnPBase<VisOdomMonoDepthPnP.Track>
Full 6-DOF visual odometry where a ranging device is assumed for pixels in the primary view and the motion is estimated
using a
Estimate1ofPnP
. Range is usually estimated using stereo cameras, structured
light or time of flight sensors. New features are added and removed as needed. Features are removed
if they are not part of the inlier feature set for some number of consecutive frames. New features are detected
and added if the inlier set falls below a threshold or every turn.
Non-linear refinement is optional and appears to provide a very modest improvement in performance. It is recommended
that motion is estimated using a P3P algorithm, which is the minimal case. Adding features every frame can be
computationally expensive, but having too few features being tracked will degrade accuracy. The algorithm was
designed to minimize magic numbers and to be insensitive to small changes in their values.
Due to the level of abstraction, it can't take full advantage of the sensors used to estimate 3D feature locations.
For example if a stereo camera is used then 3-view geometry can't be used to improve performance.-
Nested Class Summary
Nested classes/interfaces inherited from class boofcv.alg.sfm.d3.VisOdomBundlePnPBase
VisOdomBundlePnPBase.CameraModel
-
Field Summary
Fields inherited from class boofcv.alg.sfm.d3.VisOdomBundlePnPBase
bundleViso, cameraLoc, cameraModels, current_to_previous, current_to_world, first, found3D, frameManager, initialVisible, inlierTracks, listOf_world_to_frame, maxKeyFrames, minObservationsNotVisible, minObservationsTriangulate, observationsNorm, previous_to_current, profileOut, thresholdRetireTracks, totalDroppedTracksBadBundle, triangulateN, verbose, visibleTracks, world_to_frame
-
Constructor Summary
ConstructorDescriptionVisOdomMonoDepthPnP
(ModelMatcher<Se3_F64, Point2D3D> motionEstimator, ImagePixelTo3D pixelTo3D, @Nullable RefinePnP refine, PointTracker<T> tracker) Configures magic numbers and estimation algorithms. -
Method Summary
Modifier and TypeMethodDescriptionprotected void
dropVisualTrack
(PointTrack track) Given the BTrack drop all visual tracks which belong to it.long
boolean
Estimates the motion given the left camera image.void
reset()
Resets the algorithm into its original statevoid
setCamera
(CameraPinholeBrown camera) Sets the known fixed camera parametersMethods inherited from class boofcv.alg.sfm.d3.VisOdomBundlePnPBase
dropFramesFromScene, dropTracksNotVisibleAndTooFewObservations, getCurrentToWorld, performKeyFrameMaintenance, setVerbose, triangulateNotSelectedBundleTracks, updateListOfVisibleTracksForOutput
-
Constructor Details
-
VisOdomMonoDepthPnP
public VisOdomMonoDepthPnP(ModelMatcher<Se3_F64, Point2D3D> motionEstimator, ImagePixelTo3D pixelTo3D, @Nullable @Nullable RefinePnP refine, PointTracker<T> tracker) Configures magic numbers and estimation algorithms.- Parameters:
motionEstimator
- PnP motion estimator. P3P algorithm is recommended/pixelTo3D
- Computes the 3D location of pixels.refine
- Optional algorithm for refining the pose estimate. Can be null.tracker
- Point feature tracker.
-
-
Method Details
-
reset
public void reset()Resets the algorithm into its original state- Overrides:
reset
in classVisOdomBundlePnPBase<VisOdomMonoDepthPnP.Track>
-
process
Estimates the motion given the left camera image. The latest information required by ImagePixelTo3D should be passed to the class before invoking this function.- Parameters:
image
- Camera image.- Returns:
- true if successful or false if it failed
-
dropVisualTrack
Description copied from class:VisOdomBundlePnPBase
Given the BTrack drop all visual tracks which belong to it.- Specified by:
dropVisualTrack
in classVisOdomBundlePnPBase<VisOdomMonoDepthPnP.Track>
-
setCamera
Sets the known fixed camera parameters -
getFrameID
public long getFrameID()- Specified by:
getFrameID
in classVisOdomBundlePnPBase<VisOdomMonoDepthPnP.Track>
-