Package boofcv.alg.geo.pose
Class PnPStereoEstimator
java.lang.Object
boofcv.alg.geo.pose.PnPStereoEstimator
- All Implemented Interfaces:
GeoModelEstimator1<Se3_F64,Stereo2D3D>
Computes the left camera pose from a fully calibrated stereo camera system using a PnP algorithm. Observations
from the left camera are used to solve the PnP problem while observations from the right camera are used to
select the best solution if its ambiguous.
Observations past the minimum number are used just for selecting the best hypothesis.
-
Constructor Summary
ConstructorsConstructorDescriptionPnPStereoEstimator(GeoModelEstimatorN<Se3_F64, Point2D3D> alg, DistanceFromModelMultiView<Se3_F64, Point2D3D> distanceLeft, DistanceFromModelMultiView<Se3_F64, Point2D3D> distanceRight, int extraForTest) -
Method Summary
Modifier and TypeMethodDescriptionintMinimum number of points required to estimate the model.booleanprocess(List<Stereo2D3D> points, Se3_F64 estimatedModel) Estimates the model given a set of observations.voidsetLeftToRight(Se3_F64 leftToRight) voidsetLeftToRightReference(Se3_F64 leftToRight) void
-
Constructor Details
-
PnPStereoEstimator
public PnPStereoEstimator(GeoModelEstimatorN<Se3_F64, Point2D3D> alg, DistanceFromModelMultiView<Se3_F64, Point2D3D> distanceLeft, DistanceFromModelMultiView<Se3_F64, Point2D3D> distanceRight, int extraForTest) - Parameters:
extraForTest- Right camera is used so zero is the minimum number
-
-
Method Details
-
setLeftToRight
-
setLeftToRightReference
-
process
Description copied from interface:GeoModelEstimator1Estimates the model given a set of observations.- Specified by:
processin interfaceGeoModelEstimator1<Se3_F64,Stereo2D3D> - Parameters:
points- Input: Set of observations. Not modified.estimatedModel- Output: Storage for the estimated model. Modified.- Returns:
- true if successful
-
setStereoParameters
-
getMinimumPoints
public int getMinimumPoints()Description copied from interface:GeoModelEstimator1Minimum number of points required to estimate the model.- Specified by:
getMinimumPointsin interfaceGeoModelEstimator1<Se3_F64,Stereo2D3D> - Returns:
- Minimum number of points.
-