public class PruneStructureFromScene
extends java.lang.Object
| Constructor and Description |
|---|
PruneStructureFromScene(boofcv.abst.geo.bundle.SceneStructureMetric structure,
boofcv.abst.geo.bundle.SceneObservations observations) |
| Modifier and Type | Method and Description |
|---|---|
void |
pruneObservationsBehindCamera()
Check to see if a point is behind the camera which is viewing it.
|
void |
pruneObservationsByErrorRank(double inlierFraction)
Computes reprojection error for all features.
|
void |
prunePoints(int count)
Prunes Points/features with less than 'count' observations.
|
void |
prunePoints(int neighbors,
double distance)
Prune a feature it has fewer than X neighbors within Y distance.
|
void |
pruneUnusedCameras()
Prunes cameras that are not referenced by any views.
|
void |
pruneViews(int count)
Removes views with less than 'count' features visible.
|
public PruneStructureFromScene(boofcv.abst.geo.bundle.SceneStructureMetric structure,
boofcv.abst.geo.bundle.SceneObservations observations)
public void pruneObservationsByErrorRank(double inlierFraction)
prunePoints(int) and pruneViews(int) to ensure the scene is still valid.inlierFraction - Fraction of observations to keep. 0 to 1. 1 = no change. 0 = everything is pruned.public void pruneObservationsBehindCamera()
public void prunePoints(int count)
pruneViews(int) to ensure that all views have points in viewcount - Minimum number of observationspublic void prunePoints(int neighbors,
double distance)
pruneViews(int) to makes sure the graph is valid.neighbors - Number of other features which need to be near bydistance - Maximum distance a point can be to be considered a featurepublic void pruneViews(int count)
count - Prune if it has this number of views or lesspublic void pruneUnusedCameras()