public class VisOdomDualTrackPnP<T extends boofcv.struct.image.ImageBase<T>,Desc extends boofcv.struct.feature.TupleDesc>
extends java.lang.Object
PnP type algorithm.
Estimated motion is relative to left camera.| Modifier and Type | Class and Description |
|---|---|
static class |
VisOdomDualTrackPnP.LeftTrackInfo |
static class |
VisOdomDualTrackPnP.RightTrackInfo |
| Constructor and Description |
|---|
VisOdomDualTrackPnP(int thresholdAdd,
int thresholdRetire,
double epilolarTol,
boofcv.abst.feature.tracker.PointTracker<T> trackerLeft,
boofcv.abst.feature.tracker.PointTracker<T> trackerRight,
boofcv.abst.feature.describe.DescribeRegionPoint<T,Desc> describe,
boofcv.abst.feature.associate.AssociateDescription2D<Desc> assocL2R,
boofcv.abst.geo.Triangulate2ViewsMetric triangulate,
org.ddogleg.fitting.modelset.ModelMatcher<georegression.struct.se.Se3_F64,Stereo2D3D> matcher,
org.ddogleg.fitting.modelset.ModelFitter<georegression.struct.se.Se3_F64,Stereo2D3D> modelRefiner)
Specifies internal algorithms and parameters
|
| Modifier and Type | Method and Description |
|---|---|
java.util.List<boofcv.abst.feature.tracker.PointTrack> |
getCandidates()
Returns a list of active tracks that passed geometric constraints
|
georegression.struct.se.Se3_F64 |
getCurrToWorld() |
org.ddogleg.fitting.modelset.ModelMatcher<georegression.struct.se.Se3_F64,Stereo2D3D> |
getMatcher() |
int |
getTick() |
boolean |
isFault()
If there are no candidates then a fault happened.
|
boolean |
process(T left,
T right)
Updates motion estimate using the stereo pair.
|
void |
reset()
Resets the algorithm into its original state
|
void |
setCalibration(boofcv.struct.calib.StereoParameters param) |
public VisOdomDualTrackPnP(int thresholdAdd,
int thresholdRetire,
double epilolarTol,
boofcv.abst.feature.tracker.PointTracker<T> trackerLeft,
boofcv.abst.feature.tracker.PointTracker<T> trackerRight,
boofcv.abst.feature.describe.DescribeRegionPoint<T,Desc> describe,
boofcv.abst.feature.associate.AssociateDescription2D<Desc> assocL2R,
boofcv.abst.geo.Triangulate2ViewsMetric triangulate,
org.ddogleg.fitting.modelset.ModelMatcher<georegression.struct.se.Se3_F64,Stereo2D3D> matcher,
org.ddogleg.fitting.modelset.ModelFitter<georegression.struct.se.Se3_F64,Stereo2D3D> modelRefiner)
thresholdAdd - When the number of inliers is below this number new features are detectedthresholdRetire - When a feature has not been in the inlier list for this many ticks it is droppedepilolarTol - 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 righttriangulate - Triangulation for estimating 3D location from stereo pairmatcher - Robust motion model estimation with outlier rejectionmodelRefiner - Non-linear refinement of motion modelpublic void setCalibration(boofcv.struct.calib.StereoParameters param)
public void reset()
public boolean process(T left, T right)
left - Image from left cameraright - Image from right camerapublic georegression.struct.se.Se3_F64 getCurrToWorld()
public int getTick()
public boolean isFault()
public java.util.List<boofcv.abst.feature.tracker.PointTrack> getCandidates()
public org.ddogleg.fitting.modelset.ModelMatcher<georegression.struct.se.Se3_F64,Stereo2D3D> getMatcher()