| Interface | Description |
|---|---|
| Boundable |
Methods to be implemented by geometric elements that can be enclosed within
a bounding volume tree.
|
| BVFeatureQuery.ObjectDistanceCalculator | |
| BVFeatureQuery.ObjectDistanceCollector |
Utility class for collecting objects when performing
a nearest-distance search until a condition is met
(e.g.
|
| BVNodeTester |
Defines a worker class that tests two bounding volume nodes for intersection.
|
| ConvexPolygonIntersector.Listener | |
| Face.FaceFilter |
Used to select mesh faces in an application.
|
| GeometryTransformer.Constrainer |
Implements constraint operations on rigid or affine transform objects.
|
| KDComparator<T> | |
| PointInterpolationWeights |
Computes normalized weights for point-based interpolation given a reference
point and a set of support points.
|
| Class | Description |
|---|---|
| AABB | |
| AABBTree | |
| AffineTransformer |
A GeometryTransformer that implements a linear affine transformation.
|
| AffineTransformerTest | |
| BSPTree | |
| BVBoxNodeTest | |
| BVBoxNodeTester |
A worker class that tests AABB and OBB bounding boxes for intersection.
|
| BVBoxNodeTesterTest | |
| BVFeatureQuery |
Worker class for nearest feature queries using bounding volume hierarchies.
|
| BVFeatureQuery.NearestKCollector<T> |
Collects the nearest K boundables, as in a k-nearest-neighbor search
|
| BVFeatureQuery.ObjectDistanceEntry<T> |
Pair of { Object, Distance}, used by nearest object queries
|
| BVFeatureQueryTest | |
| BVIntersector |
Worker class for computing intersections using bounding volume hierarchies.
|
| BVIntersectorTest | |
| BVNode |
Base class for bounding volumes such as oriented and axis-aligned bounding
boxes.
|
| BVTree |
Base class for a bounding volume tree composed of a hierarchy of bounding
volumes.
|
| BVTreeTest | |
| ConstrainedTranslator3d |
A translational dragger that keeps its origin attached to the surface
of a PolygonalMesh.
|
| ConvexPolygon2d | |
| ConvexPolygon3d | |
| ConvexPolygon3dTest | |
| ConvexPolygonIntersector | |
| ConvexPolygonIntersectorTest | |
| CovarianceUtils |
Set of utility methods to compute and transform Covariances.
|
| CPD | |
| CPDRigidAligner | |
| CPDTest | |
| CSG |
Constructive Solid Geometry tools
|
| CVReconstruction3d |
Computer-Vision 3D reconstruction methods
|
| CVReconstruction3dTest | |
| DeformationTransformer |
Base class for GeometryTransformers that implement general deformation
fields.
|
| DeformationTransformerTest | |
| DelaunayInterpolator | |
| DelaunayInterpolatorTest | |
| DistanceGrid |
Implements a distance field on a regular 3D grid.
|
| DistanceGrid.TetDesc | |
| DistanceGridFeatureQuery |
Worker class for nearest feature queries using distance/signed distance fields
|
| DistanceGridSurfCalc |
Worker class that performs computations specifically related to the
intersection of a plane and the surface of a quadratically interpolated
distance grid.
|
| DistanceGridSurfCalc.TangentProblem |
Used to write out a surface tangent problem for debugging purposes.
|
| DistanceGridSurfCalc.TanSearchInfo | |
| DistanceGridSurfCalc.TetEdge | |
| DistanceGridSurfCalc.TetFeature | |
| DistanceGridSurfCalc.TetNode | |
| DistanceGridSurfCalc.TetPlaneIntersection | |
| DistanceGridTest | |
| DistanceGridTester |
This is a test class for SignedDistanceGrid.
|
| DistanceRecord | |
| EllipsoidTest |
This class is intended to test the computation of prinicpal curvatures and
radii for ellipsoids, based on the first and second fundamental forms.
|
| Face | |
| FaceNode | |
| FaceTest | |
| Feature |
Super class for vertices, half-edges, and faces.
|
| GeometryTransformer |
Implements geometric transformations associated with a generalized
deformation mapping, under which points
p are mapped
to deformed points p' using a function |
| GeometryTransformer.UniformScalingConstrainer |
Constrains an affine transform so that it results in
uniform scaling with no translation
|
| GeometryTransformerTest | |
| GeometryUtils |
Utility methods for geometric computation.
|
| GeometryUtilsTest |
Test class for GeometryUtils.
|
| HalfEdge |
Half-edge for 3D dimensional polyhedral objects.
|
| HalfEdgeNode | |
| HalfEdgeTest | |
| HashedPointSet | |
| ICPRegistration |
Class to perform interative closest point (ICP) registration of one mesh
onto another.
|
| InterpolatingGridBase |
Base class for regular 3D grids that interpolate values using trilinear
interpolation.
|
| InterpolatingGridTestBase |
Base class for testing subclasses of InterpolatingGridBase
|
| Intersector2d |
Used to perform 2D intersections, or solve intersection problems on the plane
|
| InverseDistanceWeights |
Computes normalized weights for point-based interpolation based on
inverse-distance weighting, given a reference point
p and a set
of support points p_i. |
| KDTree<T> |
Generic KD-Tree utility, requires a KDComparator for computing
distances between elements.
|
| KDTree.KDNode<T> |
KD node associated with a node on a KD-Tree
|
| KDTree3d |
KD-Tree based on Point3d
|
| KDTree3dTest |
Performs some basic query and speed test for KDTree3d.
|
| LaplacianSmoother |
Applies Laplacian or Taubin smoothing to a polygonal mesh.
|
| LineSegment | |
| MarchingTetrahedra |
Implements MarchingTetrahedra to generate a mesh from a scalar field defined
on a grid.
|
| MatrixNdGrid |
Implements a regular 3D grid that interpolates
MatrixNd values using
trilinear interpolation. |
| MeshBase |
A "mesh" is a geometric object defined by a set of vertices, which are then
connected in some specific way.
|
| MeshDemo |
Demonstration class which illustrates how to build a PolygonalMesh using its
addVertex and addFace methods. |
| MeshFactory |
Creates specific instances of polygonal meshes.
|
| MeshFactory.VertexMap | |
| MeshFactory.VertexSet | |
| MeshFactoryTest | |
| MeshICP |
Performs basic ICP alignment of meshes
|
| MeshICPAligner | |
| MeshInfo | |
| MeshRayIntersectionTest | |
| MeshRendererBase | |
| MeshTestBase | |
| MeshUtilities |
Methods that modify a mesh, XXX many of these methods are broken
|
| MeshUtilitiesTest | |
| NagataInterpolator |
Class that implements quadratic surface interpolation based on the paper
"Simple local interpolation of surfaces using normal vectors", by Takashi
Nagata.
|
| NagataInterpolatorTest | |
| NURBSCurve2d |
Implements a NURBS curve
|
| NURBSCurve3d |
Implements a NURBS curve
|
| NURBSCurveBase |
Base class for 2 and 3 dimensional NURBS curves
|
| NURBSMesh | |
| NURBSObject |
Base class for a NURBS curve or surface.
|
| NURBSSurface |
Implements a NURBS surface
|
| OBB | |
| OBBTree | |
| PointMesh |
Implements a mesh consisting of a set of points and possibly normals.
|
| PointMeshRenderer |
Utility class for rendering
PointMesh objects. |
| PointMeshTest |
Test class for PointMesh
|
| Polygon2d | |
| Polygon2dTest | |
| Polygon3d | |
| Polygon3dCalc | |
| Polygon3dCalcTest | |
| Polygon3dFeature | |
| Polygon3dTest | |
| PolygonalMesh |
Implements a polygonal mesh consisting of vertices, faces, and half-edges.
|
| PolygonalMeshQuery |
Provides various query methods for a PolygonalMesh.
|
| PolygonalMeshRenderer |
Utility class for rendering
PolygonalMesh objects. |
| PolygonalMeshTest | |
| PolygonIntersector |
Utility class to intersect 2D and 3D polygons.
|
| PolygonIntersectorTest | |
| PolygonVertex3d | |
| Polyline | |
| PolylineInterpolator |
Class to interpolate directions within a Polyline mesh.
|
| PolylineMesh |
Implements a mesh consisting of a set of polylines.
|
| PolylineMeshRenderer |
Utility class for rendering
PolylineMesh objects. |
| PolylineMeshTest |
Test class for PolylineMesh
|
| QuadBezierDistance2d |
Class to calculate distances between a 2D Quadratic Bezier B-spline curve
and a point in the plane.
|
| QuadraticUtils |
Utility methods for quadratic shapes and surfaces.
|
| QuadraticUtilsTest |
Utility methods for quadratic shapes and surfaces.
|
| Rectangle2d | |
| RigidTransformer |
A GeometryTransformer that implements a linear rigid body transformation.
|
| RigidTransformerTest | |
| RobustPreds |
A set of utility methods for robust intersection queries involving line
segments and faces.
|
| RobustPredsTest | |
| ScalarGrid |
Implements a regular 3D grid that interpolates scalar values using
trilinear interpolation.
|
| ScalarGridBase |
Base class for a regular 3D grid that interpolates scalar values using
trilinear interpolation.
|
| ScalarGridTest | |
| ScaledRigidTransformer3d |
Implements an affine transformation defined in homogeneous coordinates by
|
| ScaledTranslation3d |
Implements an affine transformation defined in homogeneous coordinates by
|
| SignedDistanceGrid |
Implements a signed distance field for fixed triangular mesh.
|
| SpatialHashTable<T> |
Spatial Hash Table for speeding up 3D spatial nearest neighbour searches.
3D space is partitioned into an orthogonal, equally spaced grid. |
| Sphere | |
| SphereIntersector | |
| SubdivisionVertex3d |
Holds a reference to the face and barycentric coordinates used to generate
this vertice.
|
| TetgenConvexHullTest |
Testing class for the convex hull part of TetgenTessellator.
|
| TetgenTessellator | |
| TetgenTessellatorTest | |
| TriangleIntersector | |
| TrianglePatch |
Constructus a triangular patch continuous with respect to vertex normals.
|
| TriangleTessellator |
Uses the native Triangle code developed by Jonathon Shewchuck
to create triangulated 2D meshes.
|
| TriLineIntersection | |
| TriPlaneIntersection | |
| TriTriIntersection |
A generic representation of an intersection between two triangles.
|
| VectorGrid<T extends VectorObject<T>> |
Implements a regular 3D grid that interpolates
VectorObject values
using trilinear interpolation. |
| VectorGridTest | |
| VectorNdGrid |
Implements a regular 3D grid that interpolates
VectorNd values using
trilinear interpolation. |
| Vertex2d | |
| Vertex3d |
Vertex for a 3D dimensional polyhedral object.
|
| Vertex3dList | |
| Vertex3dListTest | |
| Vertex3dNode | |
| Vertex3dTest | |
| WindingCalculator |
Computes the winding number for a point with respect to a planar 3D
polygon.
|
| WindingCalculatorTest |
Test method for the winding number calculator.
|
| Enum | Description |
|---|---|
| BVBoxNodeTester.BoxTypes |
Decsribes the type expected for the first and second bounding box.
|
| BVFeatureQuery.InsideQuery | |
| DistanceGrid.DistanceMethod |
Describes what method to use when generating distance values from
polygonal meshes.
|
| DistanceGrid.TetID |
Identifies a sub tet within a hex cell.
|
| DistanceGridFeatureQuery.InsideQuery | |
| DistanceGridSurfCalc.PlaneType | |
| GeometryTransformer.UndoState |
Describes the current undo state of this transformer.
|
| ICPRegistration.Prealign |
Specifies whether to prealign the mesh using principal component analysis
(PCA), and if so, which of the resulting PCA axes to try.
|
| MassDistribution |
Indicates how mass is distributed across the features of a geometric object
for purposes of computing its inertia.
|
| MeshFactory.FaceType |
Used by some factory methods to specify the face type
|
| MeshICP.AlignmentType | |
| OBB.Method |
Method used to generate an OBB from a set of boundables
|
| Polygon3dCalc.Plane |
Decsribes the dominant axis-aligned plane uses for computations.
|