Package boofcv.alg.sfm.d3
Class VisOdomDualTrackPnP<T extends ImageBase<T>,TD extends TupleDesc<TD>>
java.lang.Object
boofcv.alg.sfm.d3.VisOdomBundlePnPBase<VisOdomDualTrackPnP.TrackInfo>
boofcv.alg.sfm.d3.VisOdomDualTrackPnP<T,TD>
- All Implemented Interfaces:
VerbosePrint
public class VisOdomDualTrackPnP<T extends ImageBase<T>,TD extends TupleDesc<TD>>
extends VisOdomBundlePnPBase<VisOdomDualTrackPnP.TrackInfo>
Stereo visual odometry algorithm which relies on tracking features independently in the left and right images
and then matching those tracks together. The idea behind this tracker is that the expensive task of association
features between left and right cameras only needs to be done once when track is spawned. Triangulation
is used to estimate each feature's 3D location. Motion is estimated robustly using a RANSAC type algorithm
provided by the user which internally uses
PnP
type algorithm.
Estimated motion is relative to left camera.
FUTURE WORK: Save visual tracks without stereo matches and do monocular tracking on them. This is useful for stereo
systems with only a little bit of overlap.-
Nested Class Summary
Modifier and TypeClassDescriptionstatic class
A coupled track between the left and right cameras.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
ConstructorDescriptionVisOdomDualTrackPnP
(double epilolarTol, PointTracker<T> trackerLeft, PointTracker<T> trackerRight, DescribePointRadiusAngle<T, TD> describe, AssociateDescription2D<TD> assocL2R, Triangulate2ViewsMetric triangulate2, ModelMatcher<Se3_F64, Stereo2D3D> matcher, @Nullable ModelFitter<Se3_F64, Stereo2D3D> modelRefiner) Specifies internal algorithms and parameters -
Method Summary
Modifier and TypeMethodDescriptionprotected void
dropVisualTrack
(PointTrack left) Given the BTrack drop all visual tracks which belong to it.long
boolean
isFault()
If there are no candidates then a fault happened.boolean
Updates motion estimate using the stereo pair.void
reset()
Resets the algorithm into its original statevoid
setCalibration
(StereoParameters param) Specifies the stereo parameters.Methods inherited from class boofcv.alg.sfm.d3.VisOdomBundlePnPBase
dropFramesFromScene, dropTracksNotVisibleAndTooFewObservations, getCurrentToWorld, performKeyFrameMaintenance, setVerbose, triangulateNotSelectedBundleTracks, updateListOfVisibleTracksForOutput
-
Field Details
-
CAMERA_LEFT
public static final int CAMERA_LEFT- See Also:
-
CAMERA_RIGHT
public static final int CAMERA_RIGHT- See Also:
-
-
Constructor Details
-
VisOdomDualTrackPnP
public VisOdomDualTrackPnP(double epilolarTol, PointTracker<T> trackerLeft, PointTracker<T> trackerRight, DescribePointRadiusAngle<T, TD> describe, AssociateDescription2D<TD> assocL2R, Triangulate2ViewsMetric triangulate2, ModelMatcher<Se3_F64, Stereo2D3D> matcher, @Nullable @Nullable ModelFitter<Se3_F64, Stereo2D3D> modelRefiner) Specifies internal algorithms and parameters- Parameters:
epilolarTol
- Tolerance in pixels for enforcing the epipolar constrainttrackerLeft
- Tracker used for left cameratrackerRight
- Tracker used for right cameradescribe
- Describes features in tracksassocL2R
- Assocation for left to righttriangulate2
- Triangulation for estimating 3D location from stereo pairmatcher
- Robust motion model estimation with outlier rejectionmodelRefiner
- Non-linear refinement of motion model
-
-
Method Details
-
setCalibration
Specifies the stereo parameters. Note that classes which are passed into constructor are maintained outside. Example, the RANSAC distance model might need to have stereo parameters passed to it externally since there's no generic way to handle that. -
reset
public void reset()Resets the algorithm into its original state- Overrides:
reset
in classVisOdomBundlePnPBase<VisOdomDualTrackPnP.TrackInfo>
-
process
Updates motion estimate using the stereo pair.- Parameters:
left
- Image from left cameraright
- Image from right camera- Returns:
- true if motion estimate was updated and false if not
-
getFrameID
public long getFrameID()- Specified by:
getFrameID
in classVisOdomBundlePnPBase<VisOdomDualTrackPnP.TrackInfo>
-
isFault
public boolean isFault()If there are no candidates then a fault happened.- Returns:
- true if fault. false is no fault
-
dropVisualTrack
Description copied from class:VisOdomBundlePnPBase
Given the BTrack drop all visual tracks which belong to it.- Specified by:
dropVisualTrack
in classVisOdomBundlePnPBase<VisOdomDualTrackPnP.TrackInfo>
-