37 #ifndef LVR2_ALGORITHM_RAYCASTING_BVHRAYCASTER 38 #define LVR2_ALGORITHM_RAYCASTING_BVHRAYCASTER 46 #define EPSILON 0.0000001 55 template<
typename IntT>
110 float d00 = v0.dot(v0);
111 float d01 = v0.dot(v1);
112 float d11 = v1.dot(v1);
113 float d20 = v2.dot(v0);
114 float d21 = v2.dot(v1);
115 float denom = d00 * d11 - d01 * d01;
117 float u = (d11 * d20 - d01 * d21) / denom;
118 float v = (d00 * d21 - d01 * d20) / denom;
119 float w = 1.0 - v - u;
145 return (a - b).squaredNorm();
172 const unsigned int* clBVHindicesOrTriLists,
175 const float* clBVHlimits,
176 const float* clTriangleIntersectionData,
177 const unsigned int* clTriIdxList
184 #include "BVHRaycaster.tcc" 186 #endif // LVR2_ALGORITHM_RAYCASTING_BVHRAYCASTER
bool rayIntersectsBox(Vector3f origin, Ray ray, const float *boxPtr)
Calculates whether a ray intersects a box.
A struct to return the calculation results of a triangle intersection.
std::shared_ptr< MeshBuffer > MeshBufferPtr
bool castRay(const Vector3f &origin, const Vector3f &direction, IntT &intersection)
Cast a single ray onto the mesh.
TriangleIntersectionResult intersectTrianglesBVH(const unsigned int *clBVHindicesOrTriLists, Vector3f origin, Ray ray, const float *clBVHlimits, const float *clTriangleIntersectionData, const unsigned int *clTriIdxList)
Calculates the closest intersection of a raycast into a scene of triangles, given a bounding volume h...
Eigen::Vector3i Vector3i
Eigen 3D vector, integer.
Data type to store information about a ray.
Implementation of an Bounding Volume Hierarchy Tree used for ray casting.
BVHRaycaster: CPU version of BVH Raycasting: WIP.
const unsigned int m_stack_size
Eigen::Vector3f Vector3f
Eigen 3D vector, single precision.
const unsigned int * m_TriIdxList
boost::shared_array< unsigned int > indexArray
boost::shared_array< float > floatArr
const float * m_TriangleIntersectionData
float distanceSquare(const Vector3f &a, const Vector3f &b) const
Calculates the squared distance of two vectors.
BVHTree< BaseVector< float > > m_bvh
Vector3f barycentric(const Vector3f &p, const Vector3f &a, const Vector3f &b, const Vector3f &c) const
const float * m_BVHlimits
const unsigned int * m_BVHindicesOrTriLists
BVHRaycaster(const MeshBufferPtr mesh, unsigned int stack_size=64)
Constructor: Stores mesh as member.