Autoware.Auto
euclidean_cluster.hpp
Go to the documentation of this file.
1 // Copyright 2019-2020 the Autoware Foundation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 //    http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 //
15 // Co-developed by Tier IV, Inc. and Apex.AI, Inc.
18 
19 #ifndef EUCLIDEAN_CLUSTER__EUCLIDEAN_CLUSTER_HPP_
20 #define EUCLIDEAN_CLUSTER__EUCLIDEAN_CLUSTER_HPP_
21 
22 #include <autoware_auto_msgs/msg/bounding_box_array.hpp>
23 #include <autoware_auto_msgs/msg/point_clusters.hpp>
26 #include <common/types.hpp>
27 #include <string>
28 #include <vector>
29 #include <utility>
30 
31 namespace autoware
32 {
33 namespace perception
34 {
35 namespace segmentation
36 {
38 namespace euclidean_cluster
39 {
43 struct PointXYZI
44 {
45  float32_t x = 0.0f;
46  float32_t y = 0.0f;
47  float32_t z = 0.0f;
49 }; // struct PointXYZI
50 
52 class EUCLIDEAN_CLUSTER_PUBLIC PointXYZII
53 {
54 public:
55  PointXYZII() = default;
59  PointXYZII(const PointXYZI & pt, const uint32_t id);
66  PointXYZII(
67  const float32_t x,
68  const float32_t y,
69  const float32_t z,
70  const float32_t intensity,
71  const uint32_t id);
74  uint32_t get_id() const;
77  const PointXYZI & get_point() const;
78 
79 private:
80  // This could instead be a pointer; I'm pretty sure ownership would work out, but I'm
81  // uncomfortable doing it that way (12 vs 20 bytes)
82  PointXYZI m_point;
83  uint32_t m_id = 0;
84 }; // class PointXYZII
85 
88 using Clusters = autoware_auto_msgs::msg::PointClusters;
89 using Cluster = decltype(Clusters::clusters)::value_type;
90 
95 class EUCLIDEAN_CLUSTER_PUBLIC Config
96 {
97 public:
103  Config(
104  const std::string & frame_id,
105  const std::size_t min_cluster_size,
106  const std::size_t max_num_clusters);
109  std::size_t min_cluster_size() const;
112  std::size_t max_num_clusters() const;
115  const std::string & frame_id() const;
116 
117 private:
118  const std::string m_frame_id;
119  const std::size_t m_min_cluster_size;
120  const std::size_t m_max_num_clusters;
121 }; // class Config
122 
128 class EUCLIDEAN_CLUSTER_PUBLIC EuclideanCluster
129 {
130 public:
131  enum class Error : uint8_t
132  {
133  NONE = 0U,
134  TOO_MANY_CLUSTERS
135  }; // enum class Error
140  EuclideanCluster(const Config & cfg, const HashConfig & hash_cfg);
144  template<typename ... Args>
145  void insert(Args && ... args)
146  {
147  // can't do anything with return values
148  (void)m_hash.insert(
149  PointXYZII{std::forward<Args>(args)..., static_cast<uint32_t>(m_seen.size())});
150  m_seen.push_back(false);
151  }
152 
158  template<typename IT>
159  void insert(const IT begin, const IT end)
160  {
161  if ((static_cast<std::size_t>(std::distance(begin, end)) + m_hash.size()) > m_hash.capacity()) {
162  throw std::length_error{"EuclideanCluster: Multi insert would overrun capacity"};
163  }
164  for (auto it = begin; it != end; ++it) {
165  insert(*it);
166  }
167  }
168 
173  const Clusters & cluster(const builtin_interfaces::msg::Time stamp);
174 
180  void cluster(Clusters & clusters);
181 
186  Error get_error() const;
187 
194  void cleanup(Clusters & clusters);
195 
198  const Config & get_config() const;
199 
200 private:
202  struct PointXY
203  {
204  float32_t x = 0.0f;
205  float32_t y = 0.0f;
206  }; // struct PointXYZ
208  EUCLIDEAN_CLUSTER_LOCAL void cluster_impl(Clusters & clusters);
211  EUCLIDEAN_CLUSTER_LOCAL void cluster(Clusters & clusters, const PointXYZII & pt);
213  EUCLIDEAN_CLUSTER_LOCAL void add_neighbors(Cluster & cls, const PointXY pt);
215  EUCLIDEAN_CLUSTER_LOCAL static void add_point(Cluster & cls, const PointXYZII & pt);
217  EUCLIDEAN_CLUSTER_LOCAL static PointXY get_point(const Cluster & cls, const std::size_t idx);
221  EUCLIDEAN_CLUSTER_LOCAL void return_clusters(Clusters & clusters);
222 
223  const Config m_config;
224  Hash m_hash;
225  Clusters m_clusters;
226  decltype(Clusters::clusters) m_cluster_pool;
227  Error m_last_error;
228  std::vector<bool8_t> m_seen;
229 }; // class EuclideanCluster
230 
232 namespace details
233 {
239 EUCLIDEAN_CLUSTER_PUBLIC BoundingBox compute_lfit_bounding_box(Cluster & cls);
243 EUCLIDEAN_CLUSTER_PUBLIC BoundingBox compute_eigenbox(const Cluster & cls);
248 EUCLIDEAN_CLUSTER_PUBLIC
249 void compute_lfit_bounding_boxes(Clusters & clusters, BoundingBoxArray & boxes);
254 EUCLIDEAN_CLUSTER_PUBLIC
259 EUCLIDEAN_CLUSTER_PUBLIC
260 void compute_eigenboxes(const Clusters & clusters, BoundingBoxArray & boxes);
264 EUCLIDEAN_CLUSTER_PUBLIC
265 void compute_eigenboxes_with_z(const Clusters & clusters, BoundingBoxArray & boxes);
266 } // namespace details
267 } // namespace euclidean_cluster
268 } // namespace segmentation
269 } // namespace perception
270 namespace common
271 {
272 namespace geometry
273 {
274 namespace point_adapter
275 {
276 template<>
277 inline EUCLIDEAN_CLUSTER_PUBLIC auto x_(
279 {
280  return pt.get_point().x;
281 }
282 template<>
283 inline EUCLIDEAN_CLUSTER_PUBLIC auto y_(
285 {
286  return pt.get_point().y;
287 }
288 template<>
289 inline EUCLIDEAN_CLUSTER_PUBLIC auto z_(
291 {
292  return pt.get_point().z;
293 }
294 } // namespace point_adapter
295 } // namespace geometry
296 } // namespace common
297 } // namespace autoware
298 #endif // EUCLIDEAN_CLUSTER__EUCLIDEAN_CLUSTER_HPP_
autoware::perception::segmentation::euclidean_cluster::details::compute_lfit_bounding_boxes
EUCLIDEAN_CLUSTER_PUBLIC void compute_lfit_bounding_boxes(Clusters &clusters, BoundingBoxArray &boxes)
Compute lfit bounding boxes from clusters.
Definition: euclidean_cluster.cpp:337
autoware::perception::segmentation::euclidean_cluster::EuclideanCluster
implementation of euclidean clustering for point cloud segmentation This clas implicitly projects poi...
Definition: euclidean_cluster.hpp:128
visibility_control.hpp
types.hpp
This file includes common type definition.
y
DifferentialState y
Definition: kinematic_bicycle.snippet.hpp:28
autoware::perception::segmentation::euclidean_cluster::PointXYZII::get_point
const PointXYZI & get_point() const
Get core point.
Definition: euclidean_cluster.cpp:57
autoware::perception::segmentation::euclidean_cluster::PointXYZI::x
float32_t x
Definition: euclidean_cluster.hpp:45
autoware::perception::segmentation::euclidean_cluster::details::compute_eigenboxes
EUCLIDEAN_CLUSTER_PUBLIC void compute_eigenboxes(const Clusters &clusters, BoundingBoxArray &boxes)
Compute eigenboxes from clusters.
Definition: euclidean_cluster.cpp:310
autoware::common::geometry::spatial_hash::Config2d
Configuration class for a 2d spatial hash.
Definition: spatial_hash_config.hpp:342
autoware::perception::segmentation::euclidean_cluster::details::compute_eigenbox
EUCLIDEAN_CLUSTER_PUBLIC BoundingBox compute_eigenbox(const Cluster &cls)
Compute eigenbox from individual cluster.
Definition: euclidean_cluster.cpp:298
autoware::perception::segmentation::euclidean_cluster::PointXYZI
Simple point struct for memory mapping to and from PointCloud2 type.
Definition: euclidean_cluster.hpp:43
autoware::perception::segmentation::euclidean_cluster::Cluster
decltype(Clusters::clusters)::value_type Cluster
Definition: euclidean_cluster.hpp:89
autoware::perception::segmentation::euclidean_cluster::details::BoundingBoxArray
autoware_auto_msgs::msg::BoundingBoxArray BoundingBoxArray
Definition: euclidean_cluster.hpp:235
BoundingBoxArray
autoware_auto_msgs::msg::BoundingBoxArray BoundingBoxArray
Definition: tf2_autoware_auto_msgs.hpp:35
autoware::perception::segmentation::euclidean_cluster::details::BoundingBox
autoware_auto_msgs::msg::BoundingBox BoundingBox
Definition: euclidean_cluster.hpp:234
autoware::perception::segmentation::euclidean_cluster::Config
Configuration class for euclidean cluster In the future this can become a base class with subclasses ...
Definition: euclidean_cluster.hpp:95
autoware::common::geometry::point_adapter::z_
EUCLIDEAN_CLUSTER_PUBLIC auto z_(const perception::segmentation::euclidean_cluster::PointXYZII &pt)
Definition: euclidean_cluster.hpp:289
autoware::perception::segmentation::euclidean_cluster::details::compute_lfit_bounding_boxes_with_z
EUCLIDEAN_CLUSTER_PUBLIC void compute_lfit_bounding_boxes_with_z(Clusters &clusters, BoundingBoxArray &boxes)
Compute lfit bounding boxes from clusters, including z coordinate.
Definition: euclidean_cluster.cpp:349
autoware::common::types::bool8_t
bool bool8_t
Definition: types.hpp:39
autoware::common::geometry::point_adapter::x_
EUCLIDEAN_CLUSTER_PUBLIC auto x_(const perception::segmentation::euclidean_cluster::PointXYZII &pt)
Definition: euclidean_cluster.hpp:277
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::perception::segmentation::euclidean_cluster::details::compute_eigenboxes_with_z
EUCLIDEAN_CLUSTER_PUBLIC void compute_eigenboxes_with_z(const Clusters &clusters, BoundingBoxArray &boxes)
Compute eigenboxes from clusters, including z coordinate.
Definition: euclidean_cluster.cpp:322
autoware::perception::segmentation::euclidean_cluster::Hash
autoware::common::geometry::spatial_hash::SpatialHash2d< PointXYZII > Hash
Definition: euclidean_cluster.hpp:87
x
DifferentialState x
Definition: kinematic_bicycle.snippet.hpp:28
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:45
autoware::perception::segmentation::euclidean_cluster::EuclideanCluster::insert
void insert(const IT begin, const IT end)
Multi-insert.
Definition: euclidean_cluster.hpp:159
autoware::perception::segmentation::euclidean_cluster::EuclideanCluster::insert
void insert(Args &&... args)
Insert an individual point.
Definition: euclidean_cluster.hpp:145
BoundingBox
autoware_auto_msgs::msg::BoundingBox BoundingBox
Definition: tf2_autoware_auto_msgs.hpp:36
autoware::perception::segmentation::euclidean_cluster::PointXYZI::y
float32_t y
Definition: euclidean_cluster.hpp:46
spatial_hash.hpp
This file implements a spatial hash for efficient fixed-radius near neighbor queries in 2D.
autoware::perception::segmentation::euclidean_cluster::PointXYZII
Helper point for which euclidean distance is computed only once.
Definition: euclidean_cluster.hpp:52
autoware::common::geometry::spatial_hash::SpatialHash2d
SpatialHash< T, Config2d > SpatialHash2d
Definition: spatial_hash.hpp:354
autoware::common::geometry::point_adapter::y_
EUCLIDEAN_CLUSTER_PUBLIC auto y_(const perception::segmentation::euclidean_cluster::PointXYZII &pt)
Definition: euclidean_cluster.hpp:283
autoware::perception::segmentation::euclidean_cluster::Clusters
autoware_auto_msgs::msg::PointClusters Clusters
Definition: euclidean_cluster.hpp:88
autoware::perception::segmentation::euclidean_cluster::details::compute_lfit_bounding_box
EUCLIDEAN_CLUSTER_PUBLIC BoundingBox compute_lfit_bounding_box(Cluster &cls)
Compute lfit bounding box from individual cluster.
Definition: euclidean_cluster.cpp:304
autoware::perception::segmentation::euclidean_cluster::PointXYZI::intensity
float32_t intensity
Definition: euclidean_cluster.hpp:48
autoware::perception::segmentation::euclidean_cluster::EuclideanCluster::Error
Error
Definition: euclidean_cluster.hpp:131
get_open_port.end
end
Definition: scripts/get_open_port.py:23
autoware::perception::segmentation::euclidean_cluster::PointXYZI::z
float32_t z
Definition: euclidean_cluster.hpp:47