Go to the documentation of this file.
19 #ifndef EUCLIDEAN_CLUSTER__EUCLIDEAN_CLUSTER_HPP_
20 #define EUCLIDEAN_CLUSTER__EUCLIDEAN_CLUSTER_HPP_
22 #include <autoware_auto_msgs/msg/bounding_box_array.hpp>
23 #include <autoware_auto_msgs/msg/point_clusters.hpp>
35 namespace segmentation
38 namespace euclidean_cluster
74 uint32_t get_id()
const;
88 using Clusters = autoware_auto_msgs::msg::PointClusters;
89 using Cluster = decltype(Clusters::clusters)::value_type;
95 class EUCLIDEAN_CLUSTER_PUBLIC
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;
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;
144 template<
typename ... Args>
149 PointXYZII{std::forward<Args>(args)...,
static_cast<uint32_t
>(m_seen.size())});
150 m_seen.push_back(
false);
158 template<
typename IT>
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"};
164 for (
auto it = begin; it !=
end; ++it) {
173 const Clusters & cluster(
const builtin_interfaces::msg::Time stamp);
186 Error get_error()
const;
198 const Config & get_config()
const;
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);
223 const Config m_config;
226 decltype(Clusters::clusters) m_cluster_pool;
228 std::vector<bool8_t> m_seen;
248 EUCLIDEAN_CLUSTER_PUBLIC
254 EUCLIDEAN_CLUSTER_PUBLIC
259 EUCLIDEAN_CLUSTER_PUBLIC
264 EUCLIDEAN_CLUSTER_PUBLIC
274 namespace point_adapter
277 inline EUCLIDEAN_CLUSTER_PUBLIC
auto x_(
283 inline EUCLIDEAN_CLUSTER_PUBLIC
auto y_(
289 inline EUCLIDEAN_CLUSTER_PUBLIC
auto z_(
298 #endif // EUCLIDEAN_CLUSTER__EUCLIDEAN_CLUSTER_HPP_
EUCLIDEAN_CLUSTER_PUBLIC void compute_lfit_bounding_boxes(Clusters &clusters, BoundingBoxArray &boxes)
Compute lfit bounding boxes from clusters.
Definition: euclidean_cluster.cpp:337
implementation of euclidean clustering for point cloud segmentation This clas implicitly projects poi...
Definition: euclidean_cluster.hpp:128
This file includes common type definition.
DifferentialState y
Definition: kinematic_bicycle.snippet.hpp:28
const PointXYZI & get_point() const
Get core point.
Definition: euclidean_cluster.cpp:57
float32_t x
Definition: euclidean_cluster.hpp:45
EUCLIDEAN_CLUSTER_PUBLIC void compute_eigenboxes(const Clusters &clusters, BoundingBoxArray &boxes)
Compute eigenboxes from clusters.
Definition: euclidean_cluster.cpp:310
Configuration class for a 2d spatial hash.
Definition: spatial_hash_config.hpp:342
EUCLIDEAN_CLUSTER_PUBLIC BoundingBox compute_eigenbox(const Cluster &cls)
Compute eigenbox from individual cluster.
Definition: euclidean_cluster.cpp:298
Simple point struct for memory mapping to and from PointCloud2 type.
Definition: euclidean_cluster.hpp:43
decltype(Clusters::clusters)::value_type Cluster
Definition: euclidean_cluster.hpp:89
autoware_auto_msgs::msg::BoundingBoxArray BoundingBoxArray
Definition: euclidean_cluster.hpp:235
autoware_auto_msgs::msg::BoundingBoxArray BoundingBoxArray
Definition: tf2_autoware_auto_msgs.hpp:35
autoware_auto_msgs::msg::BoundingBox BoundingBox
Definition: euclidean_cluster.hpp:234
Configuration class for euclidean cluster In the future this can become a base class with subclasses ...
Definition: euclidean_cluster.hpp:95
EUCLIDEAN_CLUSTER_PUBLIC auto z_(const perception::segmentation::euclidean_cluster::PointXYZII &pt)
Definition: euclidean_cluster.hpp:289
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
bool bool8_t
Definition: types.hpp:39
EUCLIDEAN_CLUSTER_PUBLIC auto x_(const perception::segmentation::euclidean_cluster::PointXYZII &pt)
Definition: euclidean_cluster.hpp:277
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
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::common::geometry::spatial_hash::SpatialHash2d< PointXYZII > Hash
Definition: euclidean_cluster.hpp:87
DifferentialState x
Definition: kinematic_bicycle.snippet.hpp:28
float float32_t
Definition: types.hpp:45
void insert(const IT begin, const IT end)
Multi-insert.
Definition: euclidean_cluster.hpp:159
void insert(Args &&... args)
Insert an individual point.
Definition: euclidean_cluster.hpp:145
autoware_auto_msgs::msg::BoundingBox BoundingBox
Definition: tf2_autoware_auto_msgs.hpp:36
float32_t y
Definition: euclidean_cluster.hpp:46
This file implements a spatial hash for efficient fixed-radius near neighbor queries in 2D.
Helper point for which euclidean distance is computed only once.
Definition: euclidean_cluster.hpp:52
SpatialHash< T, Config2d > SpatialHash2d
Definition: spatial_hash.hpp:354
EUCLIDEAN_CLUSTER_PUBLIC auto y_(const perception::segmentation::euclidean_cluster::PointXYZII &pt)
Definition: euclidean_cluster.hpp:283
autoware_auto_msgs::msg::PointClusters Clusters
Definition: euclidean_cluster.hpp:88
EUCLIDEAN_CLUSTER_PUBLIC BoundingBox compute_lfit_bounding_box(Cluster &cls)
Compute lfit bounding box from individual cluster.
Definition: euclidean_cluster.cpp:304
float32_t intensity
Definition: euclidean_cluster.hpp:48
Error
Definition: euclidean_cluster.hpp:131
end
Definition: scripts/get_open_port.py:23
float32_t z
Definition: euclidean_cluster.hpp:47