#include <octree.h>
Classes | |
struct | Neighbour |
struct | ObjectPlaceholder |
struct | ObjectReference |
struct | ObjectSorter |
Public Types | |
typedef TemplatedOctree::BoundingBoxType | BoundingBoxType |
typedef TemplatedOctree::CenterType | CenterType |
typedef TemplatedOctree::CoordinateType | CoordType |
typedef Octree::InnerNode * | InnerNodePointer |
typedef Octree::Leaf * | LeafPointer |
typedef std::vector< Neighbour > ::iterator | NeighbourIterator |
typedef TemplatedOctree::NodeIndex | NodeIndex |
typedef TemplatedOctree::NodePointer | NodePointer |
typedef TemplatedOctree::NodeType | NodeType |
typedef ReferenceType < OBJECT_TYPE >::Type * | ObjectPointer |
typedef OBJECT_TYPE | ObjectType |
typedef SCALAR_TYPE | ScalarType |
typedef vcg::OctreeTemplate < VoxelType, SCALAR_TYPE > | TemplatedOctree |
typedef VoxelType * | VoxelPointer |
typedef vcg::Voxel | VoxelType |
typedef TemplatedOctree::ZOrderType | ZOrderType |
Public Member Functions | |
template<class OBJECT_POINT_DISTANCE_FUNCTOR , class OBJECT_MARKER > | |
ObjectPointer | GetClosest (OBJECT_POINT_DISTANCE_FUNCTOR &distance_functor, OBJECT_MARKER &, const CoordType &query_point, const ScalarType &max_distance, ScalarType &distance, CoordType &point, bool allow_zero_distance=true) |
template<class OBJECT_MARKER , class OBJECT_POINTER_CONTAINER > | |
unsigned int | GetInBox (OBJECT_MARKER &, const BoundingBoxType &query_bounding_box, OBJECT_POINTER_CONTAINER &objects) |
template<class OBJECT_POINT_DISTANCE_FUNCTOR , class OBJECT_MARKER , class OBJECT_POINTER_CONTAINER , class DISTANCE_CONTAINER , class POINT_CONTAINER > | |
unsigned int | GetInSphere (OBJECT_POINT_DISTANCE_FUNCTOR &distance_functor, OBJECT_MARKER &, const CoordType &sphere_center, const ScalarType &sphere_radius, OBJECT_POINTER_CONTAINER &objects, DISTANCE_CONTAINER &distances, POINT_CONTAINER &points, bool sort_per_distance=false, bool allow_zero_distance=false) |
template<class OBJECT_POINT_DISTANCE_FUNCTOR , class OBJECT_MARKER , class OBJECT_POINTER_CONTAINER , class DISTANCE_CONTAINER , class POINT_CONTAINER > | |
unsigned int | GetKClosest (OBJECT_POINT_DISTANCE_FUNCTOR &distance_functor, OBJECT_MARKER &, unsigned int k, const CoordType &query_point, const ScalarType &max_distance, OBJECT_POINTER_CONTAINER &objects, DISTANCE_CONTAINER &distances, POINT_CONTAINER &points, bool sort_per_distance=true, bool allow_zero_distance=true) |
Octree () | |
template<class OBJECT_ITERATOR > | |
void | Set (const OBJECT_ITERATOR &bObj, const OBJECT_ITERATOR &eObj) |
~Octree () | |
Protected Member Functions | |
int | AdjustBoundingBox (BoundingBoxType &query_bb, ScalarType &sphere_radius, const ScalarType max_allowed_distance, std::vector< NodePointer > &leaves, const int required_object_count) |
template<class OBJECT_POINTER_CONTAINER , class DISTANCE_CONTAINER , class POINT_CONTAINER > | |
int | CopyQueryResults (std::vector< Neighbour > &neighbors, const unsigned int object_count, OBJECT_POINTER_CONTAINER &objects, DISTANCE_CONTAINER &distances, POINT_CONTAINER &points) |
bool | GuessInitialBoundingBox (const CoordType &query_point, const ScalarType max_distance, ScalarType &sphere_radius, BoundingBoxType &query_bb) |
void | IncrementMark () |
void | IndexInnerNodes (NodePointer n) |
bool | IsMarked (const ObjectReference *ref) const |
void | Mark (const ObjectReference *ref) |
template<class OBJECT_POINT_DISTANCE_FUNCTOR > | |
int | RetrieveContainedObjects (const CoordType query_point, OBJECT_POINT_DISTANCE_FUNCTOR &distance_functor, const ScalarType max_allowed_distance, bool allow_zero_distance, std::vector< NodePointer > &leaves, std::vector< Neighbour > &neighbors) |
Protected Attributes | |
unsigned char | global_mark |
unsigned char * | marks |
std::vector< ObjectReference > | sorted_dataset |
Definition at line 109 of file octree.h.
typedef TemplatedOctree::BoundingBoxType vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::BoundingBoxType |
Reimplemented from vcg::OctreeTemplate< Voxel, SCALAR_TYPE >.
typedef TemplatedOctree::CenterType vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::CenterType |
Reimplemented from vcg::OctreeTemplate< Voxel, SCALAR_TYPE >.
typedef TemplatedOctree::CoordinateType vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::CoordType |
Reimplemented from vcg::SpatialIndex< OBJECT_TYPE, SCALAR_TYPE >.
typedef Octree::InnerNode* vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::InnerNodePointer |
typedef Octree::Leaf* vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::LeafPointer |
typedef std::vector< Neighbour >::iterator vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::NeighbourIterator |
typedef TemplatedOctree::NodeIndex vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::NodeIndex |
Reimplemented from vcg::OctreeTemplate< Voxel, SCALAR_TYPE >.
typedef TemplatedOctree::NodePointer vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::NodePointer |
Reimplemented from vcg::OctreeTemplate< Voxel, SCALAR_TYPE >.
typedef TemplatedOctree::NodeType vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::NodeType |
Reimplemented from vcg::OctreeTemplate< Voxel, SCALAR_TYPE >.
typedef ReferenceType<OBJECT_TYPE>::Type* vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::ObjectPointer |
typedef OBJECT_TYPE vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::ObjectType |
typedef SCALAR_TYPE vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::ScalarType |
Reimplemented from vcg::SpatialIndex< OBJECT_TYPE, SCALAR_TYPE >.
typedef vcg::OctreeTemplate< VoxelType, SCALAR_TYPE > vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::TemplatedOctree |
typedef VoxelType* vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::VoxelPointer |
Reimplemented from vcg::OctreeTemplate< Voxel, SCALAR_TYPE >.
typedef vcg::Voxel vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::VoxelType |
Reimplemented from vcg::OctreeTemplate< Voxel, SCALAR_TYPE >.
typedef TemplatedOctree::ZOrderType vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::ZOrderType |
Reimplemented from vcg::OctreeTemplate< Voxel, SCALAR_TYPE >.
vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::Octree | ( | ) | [inline] |
vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::~Octree | ( | ) | [inline] |
int vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::AdjustBoundingBox | ( | BoundingBoxType & | query_bb, | |
ScalarType & | sphere_radius, | |||
const ScalarType | max_allowed_distance, | |||
std::vector< NodePointer > & | leaves, | |||
const int | required_object_count | |||
) | [inline, protected] |
int vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::CopyQueryResults | ( | std::vector< Neighbour > & | neighbors, | |
const unsigned int | object_count, | |||
OBJECT_POINTER_CONTAINER & | objects, | |||
DISTANCE_CONTAINER & | distances, | |||
POINT_CONTAINER & | points | |||
) | [inline, protected] |
ObjectPointer vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::GetClosest | ( | OBJECT_POINT_DISTANCE_FUNCTOR & | distance_functor, | |
OBJECT_MARKER & | , | |||
const CoordType & | query_point, | |||
const ScalarType & | max_distance, | |||
ScalarType & | distance, | |||
CoordType & | point, | |||
bool | allow_zero_distance = true | |||
) | [inline] |
unsigned int vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::GetInBox | ( | OBJECT_MARKER & | , | |
const BoundingBoxType & | query_bounding_box, | |||
OBJECT_POINTER_CONTAINER & | objects | |||
) | [inline] |
unsigned int vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::GetInSphere | ( | OBJECT_POINT_DISTANCE_FUNCTOR & | distance_functor, | |
OBJECT_MARKER & | , | |||
const CoordType & | sphere_center, | |||
const ScalarType & | sphere_radius, | |||
OBJECT_POINTER_CONTAINER & | objects, | |||
DISTANCE_CONTAINER & | distances, | |||
POINT_CONTAINER & | points, | |||
bool | sort_per_distance = false , |
|||
bool | allow_zero_distance = false | |||
) | [inline] |
unsigned int vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::GetKClosest | ( | OBJECT_POINT_DISTANCE_FUNCTOR & | distance_functor, | |
OBJECT_MARKER & | , | |||
unsigned int | k, | |||
const CoordType & | query_point, | |||
const ScalarType & | max_distance, | |||
OBJECT_POINTER_CONTAINER & | objects, | |||
DISTANCE_CONTAINER & | distances, | |||
POINT_CONTAINER & | points, | |||
bool | sort_per_distance = true , |
|||
bool | allow_zero_distance = true | |||
) | [inline] |
bool vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::GuessInitialBoundingBox | ( | const CoordType & | query_point, | |
const ScalarType | max_distance, | |||
ScalarType & | sphere_radius, | |||
BoundingBoxType & | query_bb | |||
) | [inline, protected] |
void vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::IncrementMark | ( | ) | [inline, protected] |
The expansion factor used to solve the spatial queries The current expansion factor is computed on the basis of the last expansion factor and on the history of these values, through the following heuristic: current_expansion_factor = alpha*last_expansion_factor + (1.0f-alpha)*mean_expansion_factor where alpha = 1.0/3.0;
void vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::IndexInnerNodes | ( | NodePointer | n | ) | [inline, protected] |
bool vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::IsMarked | ( | const ObjectReference * | ref | ) | const [inline, protected] |
void vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::Mark | ( | const ObjectReference * | ref | ) | [inline, protected] |
int vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::RetrieveContainedObjects | ( | const CoordType | query_point, | |
OBJECT_POINT_DISTANCE_FUNCTOR & | distance_functor, | |||
const ScalarType | max_allowed_distance, | |||
bool | allow_zero_distance, | |||
std::vector< NodePointer > & | leaves, | |||
std::vector< Neighbour > & | neighbors | |||
) | [inline, protected] |
void vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::Set | ( | const OBJECT_ITERATOR & | bObj, | |
const OBJECT_ITERATOR & | eObj | |||
) | [inline] |
unsigned char vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::global_mark [protected] |
unsigned char* vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::marks [protected] |
std::vector< ObjectReference > vcg::Octree< OBJECT_TYPE, SCALAR_TYPE >::sorted_dataset [protected] |