raycast_using_kdtree.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_KDTREE_H
31 #define MCL_3DL_RAYCASTS_RAYCAST_USING_KDTREE_H
32 
33 #include <algorithm>
34 #include <cmath>
35 #include <vector>
36 
37 #include <mcl_3dl/chunked_kdtree.h>
38 #include <mcl_3dl/raycast.h>
39 #include <mcl_3dl/vec3.h>
40 
41 namespace mcl_3dl
42 {
43 template <typename POINT_TYPE>
44 class RaycastUsingKDTree : public Raycast<POINT_TYPE>
45 {
46  using typename Raycast<POINT_TYPE>::CastResult;
47 
48 public:
49  RaycastUsingKDTree(const float map_grid_size_x, const float map_grid_size_y, const float map_grid_size_z,
50  const float hit_tolerance)
51  : Raycast<POINT_TYPE>()
52  , map_grid_min_(std::min({map_grid_size_x, map_grid_size_y, map_grid_size_z}))
53  , map_grid_max_(std::max({map_grid_size_x, map_grid_size_y, map_grid_size_z}))
54  , hit_tolerance_(hit_tolerance)
55  {
56  }
57 
58  void setRay(typename ChunkedKdtree<POINT_TYPE>::Ptr kdtree, const Vec3 ray_begin, const Vec3 ray_end) final
59  {
60  kdtree_ = kdtree;
61  length_ = std::floor(((ray_end - ray_begin).norm() + hit_tolerance_) / map_grid_min_);
62  inc_ = (ray_end - ray_begin).normalized() * map_grid_min_;
63  count_ = 1;
64  pos_ = ray_begin + inc_;
65  }
66 
67  bool getNextCastResult(CastResult& result) final
68  {
69  if (count_ >= length_)
70  {
71  return false;
72  }
73  bool collision(false);
74  float sin_ang(0.0);
75 
76  const POINT_TYPE* point = nullptr;
77  POINT_TYPE center;
78  center.x = pos_.x_;
79  center.y = pos_.y_;
80  center.z = pos_.z_;
81  std::vector<int> id(1);
82  std::vector<float> sqdist(1);
83  if (kdtree_->radiusSearch(center, std::sqrt(2.0) * map_grid_max_ / 2.0, id, sqdist, 1))
84  {
85  collision = true;
86  point = &(kdtree_->getInputCloud()->points[id[0]]);
87 
88  const float d0 = std::sqrt(sqdist[0]);
89  const Vec3 pos_prev = pos_ - (inc_ * 2.0);
90  POINT_TYPE center_prev;
91  center_prev.x = pos_prev.x_;
92  center_prev.y = pos_prev.y_;
93  center_prev.z = pos_prev.z_;
94  if (kdtree_->radiusSearch(center_prev, map_grid_min_ * 2 + std::sqrt(2.0) * map_grid_max_ / 2.0, id, sqdist, 1))
95  {
96  const float d1 = std::sqrt(sqdist[0]);
97  sin_ang = fabs(d1 - d0) / (map_grid_min_ * 2.0);
98  }
99  else
100  {
101  sin_ang = 1.0;
102  }
103  }
104  result = CastResult(pos_, collision, sin_ang, point);
105 
106  ++count_;
107  pos_ += inc_;
108  return true;
109  }
110 
111 private:
115  int length_;
116  int count_;
117  const float map_grid_min_;
118  const float map_grid_max_;
119  const float hit_tolerance_;
120 };
121 
122 } // namespace mcl_3dl
123 
124 #endif // MCL_3DL_RAYCASTS_RAYCAST_USING_KDTREE_H
min
int min(int a, int b)
raycast.h
mcl_3dl::ChunkedKdtree::Ptr
std::shared_ptr< ChunkedKdtree > Ptr
Definition: chunked_kdtree.h:49
mcl_3dl::RaycastUsingKDTree::RaycastUsingKDTree
RaycastUsingKDTree(const float map_grid_size_x, const float map_grid_size_y, const float map_grid_size_z, const float hit_tolerance)
Definition: raycast_using_kdtree.h:49
mcl_3dl::RaycastUsingKDTree::pos_
Vec3 pos_
Definition: raycast_using_kdtree.h:113
mcl_3dl::Vec3::x_
float x_
Definition: vec3.h:40
mcl_3dl::RaycastUsingKDTree::kdtree_
ChunkedKdtree< POINT_TYPE >::Ptr kdtree_
Definition: raycast_using_kdtree.h:112
mcl_3dl::RaycastUsingKDTree::count_
int count_
Definition: raycast_using_kdtree.h:116
mcl_3dl::RaycastUsingKDTree::getNextCastResult
bool getNextCastResult(CastResult &result) final
Definition: raycast_using_kdtree.h:67
vec3.h
mcl_3dl::Vec3::z_
float z_
Definition: vec3.h:42
mcl_3dl::RaycastUsingKDTree
Definition: raycast_using_kdtree.h:44
mcl_3dl::Raycast
Definition: raycast.h:42
mcl_3dl::RaycastUsingKDTree::map_grid_max_
const float map_grid_max_
Definition: raycast_using_kdtree.h:118
mcl_3dl::Vec3::y_
float y_
Definition: vec3.h:41
mcl_3dl::RaycastUsingKDTree::length_
int length_
Definition: raycast_using_kdtree.h:115
mcl_3dl::RaycastUsingKDTree::setRay
void setRay(typename ChunkedKdtree< POINT_TYPE >::Ptr kdtree, const Vec3 ray_begin, const Vec3 ray_end) final
Definition: raycast_using_kdtree.h:58
mcl_3dl
Definition: chunked_kdtree.h:43
std
mcl_3dl::RaycastUsingKDTree::inc_
Vec3 inc_
Definition: raycast_using_kdtree.h:114
mcl_3dl::Raycast::CastResult
Definition: raycast.h:45
mcl_3dl::Vec3
Definition: vec3.h:37
chunked_kdtree.h
mcl_3dl::RaycastUsingKDTree::hit_tolerance_
const float hit_tolerance_
Definition: raycast_using_kdtree.h:119
mcl_3dl::RaycastUsingKDTree::map_grid_min_
const float map_grid_min_
Definition: raycast_using_kdtree.h:117


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Thu Oct 17 2024 02:18:04