raycast.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2016-2017, the mcl_3dl authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef MCL_3DL_RAYCAST_H
31 #define MCL_3DL_RAYCAST_H
32 
33 #include <mcl_3dl/vec3.h>
34 #include <mcl_3dl/chunked_kdtree.h>
35 
36 #include <vector>
37 
38 namespace mcl_3dl
39 {
40 template <typename POINT_TYPE>
41 class Raycast
42 {
43 public:
44  class CastResult
45  {
46  public:
48  bool collision_;
49  float sin_angle_;
50 
51  CastResult(const Vec3 pos, bool collision, float sin_angle)
52  : pos_(pos)
53  , collision_(collision)
54  , sin_angle_(sin_angle)
55  {
56  }
57  };
58  class Iterator
59  {
60  protected:
64  size_t count_;
65  size_t length_;
66  float grid_min_;
67  float grid_max_;
68 
69  public:
70  friend Raycast;
71 
73  typename ChunkedKdtree<POINT_TYPE>::Ptr kdtree,
74  const Vec3 begin, const Vec3 end,
75  const float grid_min, const float grid_max)
76  {
77  kdtree_ = kdtree;
78  length_ = floorf((end - begin).norm() / grid_min - sqrtf(2.0));
79  inc_ = (end - begin).normalized() * grid_min;
80  pos_ = begin + inc_;
81  count_ = 1;
82  grid_min_ = grid_min;
83  grid_max_ = grid_max;
84  }
86  {
87  ++count_;
88  pos_ += inc_;
89  return *this;
90  }
92  {
93  bool collision(false);
94  float sin_ang(0.0);
95 
96  POINT_TYPE center;
97  center.x = pos_.x_;
98  center.y = pos_.y_;
99  center.z = pos_.z_;
100  std::vector<int> id(1);
101  std::vector<float> sqdist(1);
102  if (kdtree_->radiusSearch(
103  center,
104  sqrtf(2.0) * grid_max_ / 2.0, id, sqdist, 1))
105  {
106  collision = true;
107 
108  const float d0 = sqrtf(sqdist[0]);
109  const Vec3 pos_prev = pos_ - (inc_ * 2.0);
110  POINT_TYPE center_prev;
111  center_prev.x = pos_prev.x_;
112  center_prev.y = pos_prev.y_;
113  center_prev.z = pos_prev.z_;
114  if (kdtree_->radiusSearch(
115  center_prev,
116  grid_min_ * 2 + sqrtf(2.0) * grid_max_ / 2.0, id, sqdist, 1))
117  {
118  const float d1 = sqrtf(sqdist[0]);
119  sin_ang = fabs(d1 - d0) / (grid_min_ * 2.0);
120  }
121  else
122  {
123  sin_ang = 1.0;
124  }
125  }
126  return CastResult(pos_, collision, sin_ang);
127  }
128  bool operator!=(const Iterator& a) const
129  {
130  return count_ != a.count_;
131  }
132  };
133 
134 protected:
138 
139 public:
141  typename ChunkedKdtree<POINT_TYPE>::Ptr kdtree,
142  const Vec3 begin, const Vec3 end, const float grid, const float grid_max)
143  : begin_(kdtree, begin, end, grid, grid_max)
144  , end_(kdtree, begin, end, grid, grid_max)
145  {
146  kdtree_ = kdtree;
147  end_.count_ = end_.length_;
148  }
150  {
151  return begin_;
152  }
154  {
155  return end_;
156  }
157 };
158 } // namespace mcl_3dl
159 
160 #endif // MCL_3DL_RAYCAST_H
float z_
Definition: vec3.h:40
Iterator & operator++()
Definition: raycast.h:85
CastResult operator*()
Definition: raycast.h:91
Iterator end_
Definition: raycast.h:137
std::shared_ptr< ChunkedKdtree > Ptr
bool operator!=(const Iterator &a) const
Definition: raycast.h:128
Iterator begin_
Definition: raycast.h:136
Iterator end()
Definition: raycast.h:153
Iterator(typename ChunkedKdtree< POINT_TYPE >::Ptr kdtree, const Vec3 begin, const Vec3 end, const float grid_min, const float grid_max)
Definition: raycast.h:72
TFSIMD_FORCE_INLINE Vector3 normalized() const
int radiusSearch(const POINT_TYPE &p, const float &radius, std::vector< int > &id, std::vector< float > &dist_sq, const size_t &num)
ChunkedKdtree< POINT_TYPE >::Ptr kdtree_
Definition: raycast.h:61
float y_
Definition: vec3.h:39
float x_
Definition: vec3.h:38
Iterator begin()
Definition: raycast.h:149
Raycast(typename ChunkedKdtree< POINT_TYPE >::Ptr kdtree, const Vec3 begin, const Vec3 end, const float grid, const float grid_max)
Definition: raycast.h:140
CastResult(const Vec3 pos, bool collision, float sin_angle)
Definition: raycast.h:51
ChunkedKdtree< POINT_TYPE >::Ptr kdtree_
Definition: raycast.h:135


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Mon Jul 8 2019 03:32:36