Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #ifndef MCL_3DL_RAYCAST_H
00031 #define MCL_3DL_RAYCAST_H
00032
00033 #include <mcl_3dl/vec3.h>
00034 #include <mcl_3dl/chunked_kdtree.h>
00035
00036 #include <vector>
00037
00038 namespace mcl_3dl
00039 {
00040 template <typename POINT_TYPE>
00041 class Raycast
00042 {
00043 public:
00044 class CastResult
00045 {
00046 public:
00047 Vec3 pos_;
00048 bool collision_;
00049 float sin_angle_;
00050
00051 CastResult(const Vec3 pos, bool collision, float sin_angle)
00052 : pos_(pos)
00053 , collision_(collision)
00054 , sin_angle_(sin_angle)
00055 {
00056 }
00057 };
00058 class Iterator
00059 {
00060 protected:
00061 typename ChunkedKdtree<POINT_TYPE>::Ptr kdtree_;
00062 Vec3 pos_;
00063 Vec3 inc_;
00064 size_t count_;
00065 size_t length_;
00066 float grid_min_;
00067 float grid_max_;
00068
00069 public:
00070 friend Raycast;
00071
00072 Iterator(
00073 typename ChunkedKdtree<POINT_TYPE>::Ptr kdtree,
00074 const Vec3 begin, const Vec3 end,
00075 const float grid_min, const float grid_max)
00076 {
00077 kdtree_ = kdtree;
00078 length_ = floorf((end - begin).norm() / grid_min - sqrtf(2.0));
00079 inc_ = (end - begin).normalized() * grid_min;
00080 pos_ = begin + inc_;
00081 count_ = 1;
00082 grid_min_ = grid_min;
00083 grid_max_ = grid_max;
00084 }
00085 Iterator& operator++()
00086 {
00087 ++count_;
00088 pos_ += inc_;
00089 return *this;
00090 }
00091 CastResult operator*()
00092 {
00093 bool collision(false);
00094 float sin_ang(0.0);
00095
00096 POINT_TYPE center;
00097 center.x = pos_.x_;
00098 center.y = pos_.y_;
00099 center.z = pos_.z_;
00100 std::vector<int> id(1);
00101 std::vector<float> sqdist(1);
00102 if (kdtree_->radiusSearch(
00103 center,
00104 sqrtf(2.0) * grid_max_ / 2.0, id, sqdist, 1))
00105 {
00106 collision = true;
00107
00108 const float d0 = sqrtf(sqdist[0]);
00109 const Vec3 pos_prev = pos_ - (inc_ * 2.0);
00110 POINT_TYPE center_prev;
00111 center_prev.x = pos_prev.x_;
00112 center_prev.y = pos_prev.y_;
00113 center_prev.z = pos_prev.z_;
00114 if (kdtree_->radiusSearch(
00115 center_prev,
00116 grid_min_ * 2 + sqrtf(2.0) * grid_max_ / 2.0, id, sqdist, 1))
00117 {
00118 const float d1 = sqrtf(sqdist[0]);
00119 sin_ang = fabs(d1 - d0) / (grid_min_ * 2.0);
00120 }
00121 else
00122 {
00123 sin_ang = 1.0;
00124 }
00125 }
00126 return CastResult(pos_, collision, sin_ang);
00127 }
00128 bool operator!=(const Iterator& a) const
00129 {
00130 return count_ != a.count_;
00131 }
00132 };
00133
00134 protected:
00135 typename ChunkedKdtree<POINT_TYPE>::Ptr kdtree_;
00136 Iterator begin_;
00137 Iterator end_;
00138
00139 public:
00140 Raycast(
00141 typename ChunkedKdtree<POINT_TYPE>::Ptr kdtree,
00142 const Vec3 begin, const Vec3 end, const float grid, const float grid_max)
00143 : begin_(kdtree, begin, end, grid, grid_max)
00144 , end_(kdtree, begin, end, grid, grid_max)
00145 {
00146 kdtree_ = kdtree;
00147 end_.count_ = end_.length_;
00148 }
00149 Iterator begin()
00150 {
00151 return begin_;
00152 }
00153 Iterator end()
00154 {
00155 return end_;
00156 }
00157 };
00158 }
00159
00160 #endif // MCL_3DL_RAYCAST_H