BVHRaycaster.hpp
Go to the documentation of this file.
1 
28 /*
29  * BVHRaycaster.hpp
30  *
31  * @date 25.01.2019
32  * @author Johan M. von Behren <johan@vonbehren.eu>
33  * @author Alexander Mock <amock@uos.de>
34  */
35 
36 #pragma once
37 #ifndef LVR2_ALGORITHM_RAYCASTING_BVHRAYCASTER
38 #define LVR2_ALGORITHM_RAYCASTING_BVHRAYCASTER
39 
40 #include "lvr2/io/MeshBuffer.hpp"
42 #include "lvr2/geometry/BVH.hpp"
44 #include "Intersection.hpp"
45 
46 #define EPSILON 0.0000001
47 #define PI 3.14159265
48 
49 namespace lvr2
50 {
51 
55 template<typename IntT>
56 class BVHRaycaster : public RaycasterBase<IntT> {
57 public:
61  BVHRaycaster(const MeshBufferPtr mesh, unsigned int stack_size = 64);
62 
72  bool castRay(
73  const Vector3f& origin,
74  const Vector3f& direction,
75  IntT& intersection);
76 
82  struct Ray {
86  };
87 
93  bool hit;
94  unsigned int pBestTriId;
96  float hitDist;
97  };
98 
99 protected:
100 
102  const Vector3f& p,
103  const Vector3f& a,
104  const Vector3f& b,
105  const Vector3f& c) const
106  {
107  Vector3f v0 = b - a;
108  Vector3f v1 = c - a;
109  Vector3f v2 = p - a;
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;
116 
117  float u = (d11 * d20 - d01 * d21) / denom;
118  float v = (d00 * d21 - d01 * d20) / denom;
119  float w = 1.0 - v - u;
120 
121  return Vector3f(u, v, w);
122  }
123 
125 
128 
129  const unsigned int* m_BVHindicesOrTriLists;
130  const float* m_BVHlimits;
132  const unsigned int* m_TriIdxList;
133  const unsigned int m_stack_size;
134 
135 private:
136 
143  inline float distanceSquare(const Vector3f& a, const Vector3f& b) const
144  {
145  return (a - b).squaredNorm();
146  }
147 
148 
156  bool rayIntersectsBox(Vector3f origin, Ray ray, const float* boxPtr);
157 
171  TriangleIntersectionResult intersectTrianglesBVH(
172  const unsigned int* clBVHindicesOrTriLists,
173  Vector3f origin,
174  Ray ray,
175  const float* clBVHlimits,
176  const float* clTriangleIntersectionData,
177  const unsigned int* clTriIdxList
178  );
179 
180 };
181 
182 } // namespace lvr2
183 
184 #include "BVHRaycaster.tcc"
185 
186 #endif // LVR2_ALGORITHM_RAYCASTING_BVHRAYCASTER
BVH.hpp
lvr2::floatArr
boost::shared_array< float > floatArr
Definition: DataStruct.hpp:133
lvr2::BVHRaycaster::TriangleIntersectionResult::hit
bool hit
Definition: BVHRaycaster.hpp:93
lvr2::BVHRaycaster::Ray
Data type to store information about a ray.
Definition: BVHRaycaster.hpp:82
lvr2::BVHRaycaster::m_stack_size
const unsigned int m_stack_size
Definition: BVHRaycaster.hpp:133
lvr2::indexArray
boost::shared_array< unsigned int > indexArray
Definition: DataStruct.hpp:128
p
SharedPointer p
Definition: ConvertShared.hpp:42
lvr2::BVHRaycaster::TriangleIntersectionResult
A struct to return the calculation results of a triangle intersection.
Definition: BVHRaycaster.hpp:92
lvr2::BVHRaycaster::barycentric
Vector3f barycentric(const Vector3f &p, const Vector3f &a, const Vector3f &b, const Vector3f &c) const
Definition: BVHRaycaster.hpp:101
lvr2::BVHRaycaster::m_faces
indexArray m_faces
Definition: BVHRaycaster.hpp:126
lvr2::BVHRaycaster::Ray::rayDirSign
Vector3i rayDirSign
Definition: BVHRaycaster.hpp:85
lvr2::BVHRaycaster::TriangleIntersectionResult::pointHit
Vector3f pointHit
Definition: BVHRaycaster.hpp:95
lvr2::BVHRaycaster::rayIntersectsBox
bool rayIntersectsBox(Vector3f origin, Ray ray, const float *boxPtr)
Calculates whether a ray intersects a box.
lvr2::BVHRaycaster::m_BVHlimits
const float * m_BVHlimits
Definition: BVHRaycaster.hpp:130
lvr2::BVHRaycaster::m_vertices
floatArr m_vertices
Definition: BVHRaycaster.hpp:127
lvr2::BVHRaycaster::TriangleIntersectionResult::hitDist
float hitDist
Definition: BVHRaycaster.hpp:96
lvr2::BVHRaycaster::m_TriIdxList
const unsigned int * m_TriIdxList
Definition: BVHRaycaster.hpp:132
lvr2::Vector3f
Eigen::Vector3f Vector3f
Eigen 3D vector, single precision.
Definition: MatrixTypes.hpp:118
lvr2::BVHRaycaster::m_bvh
BVHTree< BaseVector< float > > m_bvh
Definition: BVHRaycaster.hpp:124
lvr2::BVHRaycaster::castRay
bool castRay(const Vector3f &origin, const Vector3f &direction, IntT &intersection)
Cast a single ray onto the mesh.
MatrixTypes.hpp
lvr2::BVHTree
Implementation of an Bounding Volume Hierarchy Tree used for ray casting.
Definition: BVH.hpp:61
Intersection.hpp
lvr2::BVHRaycaster::TriangleIntersectionResult::pBestTriId
unsigned int pBestTriId
Definition: BVHRaycaster.hpp:94
lvr2::BVHRaycaster::Ray::invDir
Vector3f invDir
Definition: BVHRaycaster.hpp:84
MeshBuffer.hpp
lvr2::BVHRaycaster::distanceSquare
float distanceSquare(const Vector3f &a, const Vector3f &b) const
Calculates the squared distance of two vectors.
Definition: BVHRaycaster.hpp:143
lvr2
Definition: BaseBufferManipulators.hpp:39
lvr2::MeshBufferPtr
std::shared_ptr< MeshBuffer > MeshBufferPtr
Definition: MeshBuffer.hpp:217
lvr2::Vector3i
Eigen::Vector3i Vector3i
Eigen 3D vector, integer.
Definition: MatrixTypes.hpp:124
lvr2::BVHRaycaster
BVHRaycaster: CPU version of BVH Raycasting: WIP.
Definition: BVHRaycaster.hpp:56
lvr2::BVHRaycaster::m_BVHindicesOrTriLists
const unsigned int * m_BVHindicesOrTriLists
Definition: BVHRaycaster.hpp:129
lvr2::BVHRaycaster::Ray::dir
Vector3f dir
Definition: BVHRaycaster.hpp:83
lvr2::BVHRaycaster::intersectTrianglesBVH
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...
mesh
HalfEdgeMesh< Vec > mesh
Definition: src/tools/lvr2_gs_reconstruction/Main.cpp:26
lvr2::RaycasterBase
RaycasterBase interface.
Definition: RaycasterBase.hpp:53
lvr2::BVHRaycaster::m_TriangleIntersectionData
const float * m_TriangleIntersectionData
Definition: BVHRaycaster.hpp:131
RaycasterBase.hpp
lvr2::BVHRaycaster::BVHRaycaster
BVHRaycaster(const MeshBufferPtr mesh, unsigned int stack_size=64)
Constructor: Stores mesh as member.


lvr2
Author(s): Thomas Wiemann , Sebastian Pütz , Alexander Mock , Lars Kiesow , Lukas Kalbertodt , Tristan Igelbrink , Johan M. von Behren , Dominik Feldschnieders , Alexander Löhr
autogenerated on Wed Mar 2 2022 00:37:22