These are some container definitions. More...
Namespaces | |
namespace | AngleFunctions |
namespace | ContainerFunctions |
namespace | ContainerTags |
namespace | CoordinateSystem |
namespace | Diameter |
namespace | KdTree |
namespace | MathFunctions |
namespace | MyContainers |
namespace | MyMatrix |
This These are some small matrix definitions. | |
namespace | PointFunctions |
namespace | RandomGenerators |
namespace | TypeDefsPoints |
Classes | |
class | AABB |
class | ConvexHull2D |
class | DiameterEstimator |
class | Exception |
struct | GlobalConfigs |
class | MinAreaRectangle |
struct | MyMatrixIOFormat |
class | OOBB |
class | ProjectedPointSet |
Functions | |
template<typename Derived > | |
APPROXMVBB_EXPORT OOBB | approximateMVBB (const MatrixBase< Derived > &points, const PREC epsilon, const unsigned int pointSamples=400, const unsigned int gridSize=5, const unsigned int mvbbDiamOptLoops=0, const unsigned int mvbbGridSearchOptLoops=6, std::size_t seed=ApproxMVBB::RandomGenerators::defaultSeed) |
template<typename Derived > | |
APPROXMVBB_EXPORT OOBB | approximateMVBBDiam (const MatrixBase< Derived > &points, const PREC epsilon, const unsigned int optLoops=10, std::size_t seed=ApproxMVBB::RandomGenerators::defaultSeed) |
template<typename Derived > | |
APPROXMVBB_EXPORT OOBB | approximateMVBBGridSearch (const MatrixBase< Derived > &points, OOBB oobb, PREC epsilon, const unsigned int gridSize=5, const unsigned int optLoops=6, PREC volumeAcceptFactor=1e-6, PREC minBoxExtent=1e-12) |
template<typename Derived > | |
APPROXMVBB_EXPORT OOBB | optimizeMVBB (const MatrixBase< Derived > &points, OOBB oobb, unsigned int nLoops=10, PREC volumeAcceptFactor=1e-6, PREC minBoxExtent=1e-12) |
template<typename Derived > | |
ApproxMVBB_DEFINE_MATRIX_TYPES ApproxMVBB_DEFINE_POINTS_CONFIG_TYPES APPROXMVBB_EXPORT void | samplePointsGrid (Matrix3Dyn &newPoints, const MatrixBase< Derived > &points, const unsigned int nPoints, OOBB &oobb, std::size_t seed=ApproxMVBB::RandomGenerators::defaultSeed) |
These are some container definitions.
APPROXMVBB_EXPORT OOBB ApproxMVBB::approximateMVBB | ( | const MatrixBase< Derived > & | points, |
const PREC | epsilon, | ||
const unsigned int | pointSamples = 400 , |
||
const unsigned int | gridSize = 5 , |
||
const unsigned int | mvbbDiamOptLoops = 0 , |
||
const unsigned int | mvbbGridSearchOptLoops = 6 , |
||
std::size_t | seed = ApproxMVBB::RandomGenerators::defaultSeed |
||
) |
Definition at line 339 of file ComputeApproxMVBB.hpp.
APPROXMVBB_EXPORT OOBB ApproxMVBB::approximateMVBBDiam | ( | const MatrixBase< Derived > & | points, |
const PREC | epsilon, | ||
const unsigned int | optLoops = 10 , |
||
std::size_t | seed = ApproxMVBB::RandomGenerators::defaultSeed |
||
) |
Function to optimize oriented bounding box volume. This constructs an approximation of a tightly fitted bounding box by computing the diameter d in 3d and afterwards the projection of the points in the plane perpendicular to direction d and then the diameter f in 2d and extruding the OOBB in 2d to the final OOBB approximation in 3d.
Definition at line 301 of file ComputeApproxMVBB.hpp.
APPROXMVBB_EXPORT OOBB ApproxMVBB::approximateMVBBGridSearch | ( | const MatrixBase< Derived > & | points, |
OOBB | oobb, | ||
PREC | epsilon, | ||
const unsigned int | gridSize = 5 , |
||
const unsigned int | optLoops = 6 , |
||
PREC | volumeAcceptFactor = 1e-6 , |
||
PREC | minBoxExtent = 1e-12 |
||
) |
Function to optimize oriented bounding box volume. This performs an exhaustive grid search over a given tighly fitted bounding box (use approximateMVBBDiam) to find a tighter volume.
gridSize | is half the grid size of the 3d test grid in each direction, for example gridDimX , gridDimY, gridDimZ = [-gridSize,gridSize] |
optLoops | how many optimization loops are preformed for the oobb computed in the given discrete sampled direction in the grid (see optimizeMVBB) |
volumeAcceptFactor | is volumeAcceptTol = oobb.volume * volumeAcceptFactor, which determines the tolerance when a new volume is accepted |
minBoxExtent | is the minmum extent direction a box must have, to make the volume not zero and comparable to other volumes which is useful for degenerate cases, such as all points in a surface |
Definition at line 234 of file ComputeApproxMVBB.hpp.
APPROXMVBB_EXPORT OOBB ApproxMVBB::optimizeMVBB | ( | const MatrixBase< Derived > & | points, |
OOBB | oobb, | ||
unsigned int | nLoops = 10 , |
||
PREC | volumeAcceptFactor = 1e-6 , |
||
PREC | minBoxExtent = 1e-12 |
||
) |
Function to optimize oriented bounding box volume. Projecting nLoops times into the direction of the axis of the current oobb, constructing the mvbb and overwriting the current oobb if volume is smaller
volumeAcceptFactor | is volumeAcceptTol = oobb.volume * volumeAcceptFactor, which determines the tolerance when a new volume is accepted |
minBoxExtent | is the minmum extent direction a box must have, to make the volume not zero and comparable to other volumes which is useful for degenerate cases, such as all points in a surface |
Definition at line 164 of file ComputeApproxMVBB.hpp.
ApproxMVBB_DEFINE_MATRIX_TYPES ApproxMVBB_DEFINE_POINTS_CONFIG_TYPES APPROXMVBB_EXPORT void ApproxMVBB::samplePointsGrid | ( | Matrix3Dyn & | newPoints, |
const MatrixBase< Derived > & | points, | ||
const unsigned int | nPoints, | ||
OOBB & | oobb, | ||
std::size_t | seed = ApproxMVBB::RandomGenerators::defaultSeed |
||
) |
We are given a point set, and (hopefully) a tight fitting bounding box. We compute a sample of the given size nPoints that represents the point-set. The only guarenteed is that if we use sample of size m, we get an approximation of quality about 1/{m}. Note that we pad the sample if necessary to get the desired size. This function changes the oobb and sets the z Axis to the greates extent!
nPoints | needs to be greater or equal than 2 |
Definition at line 40 of file ComputeApproxMVBB.hpp.