raycast_using_dda.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2020, 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_RAYCASTS_RAYCAST_USING_DDA_H
31 #define MCL_3DL_RAYCASTS_RAYCAST_USING_DDA_H
32 
33 #include <algorithm>
34 #include <cmath>
35 #include <limits>
36 #include <numeric>
37 #include <unordered_map>
38 #include <vector>
39 
40 #include <mcl_3dl/chunked_kdtree.h>
41 #include <mcl_3dl/raycast.h>
42 #include <mcl_3dl/vec3.h>
43 #include <pcl/common/common.h>
44 #include <pcl/point_cloud.h>
45 
46 #include <Eigen/Core>
47 
48 namespace mcl_3dl
49 {
50 template <typename POINT_TYPE>
51 class RaycastUsingDDA : public Raycast<POINT_TYPE>
52 {
53  using typename Raycast<POINT_TYPE>::CastResult;
54 
55 public:
56  RaycastUsingDDA(const double map_grid_size_x, const double map_grid_size_y, const double map_grid_size_z,
57  const double dda_grid_size, const double ray_angle_half, const double hit_tolerance)
58  : Raycast<POINT_TYPE>()
59  , min_dist_thr_sq_(std::pow(map_grid_size_x, 2) + std::pow(map_grid_size_y, 2) + std::pow(map_grid_size_y, 2))
60  , dda_grid_size_(dda_grid_size)
61  , ray_angle_half_(ray_angle_half)
62  , hit_tolerance_(hit_tolerance)
63  {
64  }
65 
66  void setRay(typename ChunkedKdtree<POINT_TYPE>::Ptr kdtree, const Vec3 ray_begin, const Vec3 ray_end_org) final
67  {
68  kdtree_ = kdtree;
70  if (!isPointWithinMap(ray_begin))
71  {
72  max_movement_ = 0;
73  pos_ = 0;
74  return;
75  }
76  ray_begin_ = ray_begin;
77  ray_direction_vector_ = (ray_end_org - ray_begin).normalized();
78  const Vec3 ray_end = ray_end_org + ray_direction_vector_ * hit_tolerance_;
79  begin_index_ = toIndex(ray_begin);
80  end_index_ = toIndex(ray_end);
81  const Eigen::Vector3i distance_index = end_index_ - begin_index_;
82  pos_ = 0;
83  max_movement_ = std::abs(distance_index[0]) + std::abs(distance_index[1]) + std::abs(distance_index[2]);
84  step_ = Eigen::Vector3i((distance_index[0] < 0) ? -1 : 1, (distance_index[1] < 0) ? -1 : 1,
85  (distance_index[2] < 0) ? -1 : 1);
86 
88  for (int i = 0; i < 3; ++i)
89  {
90  if (distance_index[i] == 0)
91  {
92  initial_edges_[i] = std::numeric_limits<double>::infinity();
93  t_delta_[i] = std::numeric_limits<double>::infinity();
94  }
95  else
96  {
97  const double nearest = (ray_direction_vector_[i] < 0) ? begin_index_[i] * dda_grid_size_ + min_p_[i] :
98  (begin_index_[i] + 1) * dda_grid_size_ + min_p_[i];
99  initial_edges_[i] = std::abs((nearest - ray_begin[i]) / ray_direction_vector_[i]);
100  t_delta_[i] = std::abs(dda_grid_size_ / ray_direction_vector_[i]);
101  }
102  }
104  }
105 
106  bool getNextCastResult(CastResult& result) final
107  {
108  ++pos_;
109  if (pos_ >= max_movement_)
110  {
111  return false;
112  }
113 
114  if (t_max_[0] < t_max_[1])
115  {
116  if (t_max_[0] < t_max_[2])
117  {
118  if (!incrementIndex(0))
119  {
120  return false;
121  }
122  }
123  else
124  {
125  if (!incrementIndex(2))
126  {
127  return false;
128  }
129  }
130  }
131  else
132  {
133  if (t_max_[1] < t_max_[2])
134  {
135  if (!incrementIndex(1))
136  {
137  return false;
138  }
139  }
140  else
141  {
142  if (!incrementIndex(2))
143  {
144  return false;
145  }
146  }
147  }
148  const POINT_TYPE* collided_point = hasIntersection(current_index_);
149  if (collided_point)
150  {
151  // TODO(nhatao): Implement estimation of the angle of incidence.
152  result = { fromIndex(current_index_), true, 1.0, collided_point };
153  }
154  else
155  {
156  result = { fromIndex(current_index_), false, 1.0, collided_point };
157  }
158  return true;
159  }
160 
161 private:
163  {
164  if (!kdtree_->getInputCloud())
165  {
166  return;
167  }
168  if ((kdtree_->getInputCloud()->header.stamp == point_cloud_header_.stamp) && !points_.empty())
169  {
170  return;
171  }
172  const typename pcl::PointCloud<POINT_TYPE>::ConstPtr& input = kdtree_->getInputCloud();
173  point_cloud_header_ = input->header;
174 
175  pcl::getMinMax3D(*input, min_p_, max_p_);
176  int point_total = 1;
177  for (int i = 0; i < 3; ++i)
178  {
179  map_size_[i] = static_cast<size_t>((max_p_[i] - min_p_[i]) / dda_grid_size_) + 1;
180  point_total *= map_size_[i];
181  }
182 
183  points_.clear();
184  point_exists_.resize(point_total);
185  std::fill(point_exists_.begin(), point_exists_.end(), 0);
186  for (const auto& p : *input)
187  {
188  setExists(&p);
189  }
190  }
191 
192  bool incrementIndex(const int i)
193  {
194  current_index_[i] += step_[i];
195  // Do not increment t_max to reduce calcuration errors
196  t_max_[i] = initial_edges_[i] + t_delta_[i] * std::abs(current_index_[i] - begin_index_[i]);
197  if (current_index_[i] < 0 || map_size_[i] <= current_index_[i])
198  {
200  return false;
201  }
202  return true;
203  }
204 
205  Eigen::Vector3i toIndex(const Vec3& point) const
206  {
207  return Eigen::Vector3i(static_cast<int>((point[0] - min_p_[0]) / dda_grid_size_),
208  static_cast<int>((point[1] - min_p_[1]) / dda_grid_size_),
209  static_cast<int>((point[2] - min_p_[2]) / dda_grid_size_));
210  }
211 
212  Eigen::Vector3i toIndex(const POINT_TYPE* point) const
213  {
214  return Eigen::Vector3i(static_cast<int>((point->x - min_p_[0]) / dda_grid_size_),
215  static_cast<int>((point->y - min_p_[1]) / dda_grid_size_),
216  static_cast<int>((point->z - min_p_[2]) / dda_grid_size_));
217  }
218 
219  Vec3 fromIndex(const Eigen::Vector3i& index) const
220  {
221  return Vec3((index[0] + 0.5) * dda_grid_size_ + min_p_[0], (index[1] + 0.5) * dda_grid_size_ + min_p_[1],
222  (index[2] + 0.5) * dda_grid_size_ + min_p_[2]);
223  }
224 
225  size_t getArrayIndex(const Eigen::Vector3i& cell) const
226  {
227  return static_cast<size_t>(cell[0] + cell[1] * map_size_[0] + cell[2] * (map_size_[0] * map_size_[1]));
228  }
229 
230  void setExists(const POINT_TYPE* point)
231  {
232  const size_t array_index = getArrayIndex(toIndex(point));
233  point_exists_[array_index] = 1;
234  points_[array_index].push_back(point);
235  }
236 
237  const POINT_TYPE* hasIntersection(const Eigen::Vector3i& target_cell) const
238  {
239  const size_t array_index = getArrayIndex(target_cell);
240  if (!point_exists_[array_index])
241  {
242  return nullptr;
243  }
244  for (const POINT_TYPE* target_org : points_.find(array_index)->second)
245  {
246  const Vec3 target_rel(target_org->x - ray_begin_[0], target_org->y - ray_begin_[1],
247  target_org->z - ray_begin_[2]);
248  const double dist_to_perpendicular_foot = std::abs(target_rel.dot(ray_direction_vector_));
249  const double dist_threshold_sq =
250  std::max(std::pow(ray_angle_half_ * dist_to_perpendicular_foot, 2), min_dist_thr_sq_);
251  const double dist_sq = target_rel.dot(target_rel) - dist_to_perpendicular_foot * dist_to_perpendicular_foot;
252  if (dist_sq < dist_threshold_sq)
253  {
254  return target_org;
255  }
256  }
257  return nullptr;
258  }
259 
260  bool isPointWithinMap(const Vec3& point) const
261  {
262  for (int i = 0; i < 3; ++i)
263  {
264  if ((point[i] < min_p_[i]) || (max_p_[i] < point[i]))
265  {
266  return false;
267  }
268  }
269  return true;
270  }
271 
273  const double min_dist_thr_sq_;
274  const double dda_grid_size_;
275  const double ray_angle_half_;
276  const double hit_tolerance_;
277 
278  Eigen::Vector3i map_size_;
279  pcl::PCLHeader point_cloud_header_;
280 
281  std::vector<uint8_t> point_exists_;
282  std::unordered_map<size_t, std::vector<const POINT_TYPE*>> points_;
283  Eigen::Vector4f min_p_;
284  Eigen::Vector4f max_p_;
285 
286  Eigen::Vector3i begin_index_;
287  Eigen::Vector3i end_index_;
291  int pos_;
294  Eigen::Vector3i current_index_;
296  Eigen::Vector3i step_;
297 };
298 
299 } // namespace mcl_3dl
300 
301 #endif // MCL_3DL_RAYCASTS_RAYCAST_USING_DDA_H
bool isPointWithinMap(const Vec3 &point) const
Eigen::Vector3i toIndex(const Vec3 &point) const
pcl::PCLHeader point_cloud_header_
void setExists(const POINT_TYPE *point)
constexpr float dot(const Vec3 &q) const
Definition: vec3.h:139
std::shared_ptr< ChunkedKdtree > Ptr
std::vector< uint8_t > point_exists_
Eigen::Vector3i current_index_
TFSIMD_FORCE_INLINE Vector3 normalized() const
RaycastUsingDDA(const double map_grid_size_x, const double map_grid_size_y, const double map_grid_size_z, const double dda_grid_size, const double ray_angle_half, const double hit_tolerance)
bool incrementIndex(const int i)
size_t getArrayIndex(const Eigen::Vector3i &cell) const
ChunkedKdtree< POINT_TYPE >::Ptr kdtree_
void setRay(typename ChunkedKdtree< POINT_TYPE >::Ptr kdtree, const Vec3 ray_begin, const Vec3 ray_end_org) final
INLINE Rall1d< T, V, S > pow(const Rall1d< T, V, S > &arg, double m)
bool getNextCastResult(CastResult &result) final
Vec3 fromIndex(const Eigen::Vector3i &index) const
const POINT_TYPE * hasIntersection(const Eigen::Vector3i &target_cell) const
Eigen::Vector3i toIndex(const POINT_TYPE *point) const
std::unordered_map< size_t, std::vector< const POINT_TYPE * > > points_


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Wed May 12 2021 02:16:29