Package boofcv.alg.sfm.d3
Class VisOdomStereoQuadPnP<T extends boofcv.struct.image.ImageGray<T>,TD extends boofcv.struct.feature.TupleDesc>
- java.lang.Object
-
- boofcv.alg.sfm.d3.VisOdomStereoQuadPnP<T,TD>
-
- All Implemented Interfaces:
org.ddogleg.struct.VerbosePrint
public class VisOdomStereoQuadPnP<T extends boofcv.struct.image.ImageGray<T>,TD extends boofcv.struct.feature.TupleDesc> extends java.lang.Object implements org.ddogleg.struct.VerbosePrintStereo visual odometry algorithm which associates image features across two stereo pairs for a total of four images. Image features are first matched between left and right images while applying epipolar constraints. Then the two more recent sets of stereo images are associated with each other in a left to left and right to right fashion. Features which are consistently matched across all four images are saved in a list. RANSAC is then used to remove false positives and estimate camera motion using aPnPtype algorithm. Motion is estimated using PNP with RANSAC. The initial 3D location of a feature is found using the stereo pair in the key frame. After the initial motion is found it can optionally be refined. Now that the location of all four cameras is known points are triangulated again using all four views. Then the optional final step is to run bundle adjustment. Features are uniquely tracked from one image to the next. This allows the refined 3D location of each feature to benefit future frames instead of being lost. However, due to the nature of the DDA image tracker, losing track is quite common. The previous stereo pair is referred to as the key frame because it's the reference point that motion is estimated relative to. Inside the code each camera is some times referred to by number. 0 = left camera key frame. 1 = key camera previous frame. 2 = left camera current frame. 3 = right camera current frame.
-
-
Nested Class Summary
Nested Classes Modifier and Type Class Description static classVisOdomStereoQuadPnP.ImageInfo<TD>Storage for detected features inside an imagestatic classVisOdomStereoQuadPnP.SetMatchesCorrespondences between imagesstatic classVisOdomStereoQuadPnP.TrackQuad3D coordinate of the feature and its observed location in each image
-
Field Summary
Fields Modifier and Type Field Description protected java.io.PrintStreamprofileOutprotected java.io.PrintStreamverbose
-
Constructor Summary
Constructors Constructor Description VisOdomStereoQuadPnP(boofcv.abst.feature.detdesc.DetectDescribePoint<T,TD> detector, boofcv.abst.feature.associate.AssociateDescription<TD> assocF2F, boofcv.abst.feature.associate.AssociateDescription2D<TD> 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, boofcv.abst.geo.bundle.BundleAdjustment<boofcv.abst.geo.bundle.SceneStructureMetric> bundleAdjustment)Specifies internal algorithms
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description georegression.struct.se.Se3_F64getLeftToWorld()booleanprocess(T left, T right)Estimates camera egomotion from the stereo pairvoidreset()Resets the algorithm into its original statevoidsetCalibration(boofcv.struct.calib.StereoParameters param)Sets and saves the stereo camera's calibrationvoidsetVerbose(java.io.PrintStream out, java.util.Set<java.lang.String> configuration)
-
-
-
Constructor Detail
-
VisOdomStereoQuadPnP
public VisOdomStereoQuadPnP(boofcv.abst.feature.detdesc.DetectDescribePoint<T,TD> detector, boofcv.abst.feature.associate.AssociateDescription<TD> assocF2F, boofcv.abst.feature.associate.AssociateDescription2D<TD> 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, boofcv.abst.geo.bundle.BundleAdjustment<boofcv.abst.geo.bundle.SceneStructureMetric> bundleAdjustment)
Specifies internal algorithms- Parameters:
detector- Estimates image featuresassocF2F- Association algorithm used for left to left and right to rightassocL2R- Assocation algorithm used for left to righttriangulate- Used to estimate 3D location of a feature using stereo correspondencematcher- Robust model estimation. Often RANSACmodelRefiner- Non-linear refinement of motion estimation
-
-
Method Detail
-
setCalibration
public void setCalibration(boofcv.struct.calib.StereoParameters param)
Sets and saves the stereo camera's calibration
-
reset
public void reset()
Resets the algorithm into its original state
-
process
public boolean process(T left, T right)
Estimates camera egomotion from the stereo pair- Parameters:
left- Image from left cameraright- Image from right camera- Returns:
- true if motion was estimated and false if not
-
getLeftToWorld
public georegression.struct.se.Se3_F64 getLeftToWorld()
-
setVerbose
public void setVerbose(@Nullable java.io.PrintStream out, @Nullable java.util.Set<java.lang.String> configuration)- Specified by:
setVerbosein interfaceorg.ddogleg.struct.VerbosePrint
-
-