Autoware.Auto
point_cloud_utils.hpp
Go to the documentation of this file.
1 // Copyright 2017-2020 the Autoware Foundation, Arm Limited
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 LIDAR_UTILS__POINT_CLOUD_UTILS_HPP_
20 #define LIDAR_UTILS__POINT_CLOUD_UTILS_HPP_
21 
23 
24 #include <autoware_auto_perception_msgs/msg/point_clusters.hpp>
25 #include <common/types.hpp>
26 #include <geometry/common_3d.hpp>
27 #include <geometry_msgs/msg/transform_stamped.hpp>
29 #include <point_cloud_msg_wrapper/point_cloud_msg_wrapper.hpp>
30 #include <sensor_msgs/msg/point_cloud2.hpp>
31 #include <sensor_msgs/point_cloud2_iterator.hpp>
32 
33 #include <Eigen/Core>
34 #include <Eigen/Geometry>
35 
36 #include <atomic>
37 #include <limits>
38 #include <memory>
39 #include <string>
40 #include <utility>
41 #include <vector>
42 
43 
44 namespace autoware
45 {
46 namespace common
47 {
48 namespace comp = helper_functions::comparisons;
49 namespace lidar_utils
50 {
51 
52 using CloudModifier =
53  point_cloud_msg_wrapper::PointCloud2Modifier<autoware::common::types::PointXYZI>;
54 using CloudView = point_cloud_msg_wrapper::PointCloud2View<autoware::common::types::PointXYZI>;
55 
56 using CloudModifierRing =
57  point_cloud_msg_wrapper::PointCloud2Modifier<autoware::common::types::PointXYZIF>;
58 using CloudViewRing = point_cloud_msg_wrapper::PointCloud2View<autoware::common::types::PointXYZIF>;
59 
61 
65 
68 static const uint32_t MAX_SCAN_POINTS = 57872U;
69 
73 LIDAR_UTILS_PUBLIC
74 std::size_t index_after_last_safe_byte_index(const sensor_msgs::msg::PointCloud2 & msg) noexcept;
75 
77 {
78  std::size_t point_step;
79  std::size_t data_length;
80 };
81 
87 
92 LIDAR_UTILS_PUBLIC
93 std::pair<autoware_auto_perception_msgs::msg::PointClusters::_points_type::iterator,
94  autoware_auto_perception_msgs::msg::PointClusters::_points_type::iterator>
95 get_cluster(autoware_auto_perception_msgs::msg::PointClusters & clusters, const std::size_t cls_id);
96 
101 LIDAR_UTILS_PUBLIC
102 std::pair<autoware_auto_perception_msgs::msg::PointClusters::_points_type::const_iterator,
103  autoware_auto_perception_msgs::msg::PointClusters::_points_type::const_iterator>
105  const autoware_auto_perception_msgs::msg::PointClusters & clusters,
106  const std::size_t cls_id);
107 
108 
112 LIDAR_UTILS_PUBLIC bool8_t
113 has_intensity_and_throw_if_no_xyz(const PointCloud2::SharedPtr & cloud);
114 
118 LIDAR_UTILS_PUBLIC bool8_t
120 
121 template<typename T>
123 
124 template<>
126 {
127  static constexpr auto DATATYPE = sensor_msgs::msg::PointField::INT8;
128 };
129 
130 template<>
132 {
133  static constexpr auto DATATYPE = sensor_msgs::msg::PointField::UINT8;
134 };
135 
136 template<>
138 {
139  static constexpr auto DATATYPE = sensor_msgs::msg::PointField::INT16;
140 };
141 
142 template<>
144 {
145  static constexpr auto DATATYPE = sensor_msgs::msg::PointField::UINT16;
146 };
147 
148 template<>
150 {
151  static constexpr auto DATATYPE = sensor_msgs::msg::PointField::INT32;
152 };
153 
154 template<>
156 {
157  static constexpr auto DATATYPE = sensor_msgs::msg::PointField::UINT32;
158 };
159 
160 template<>
162 {
163  static constexpr auto DATATYPE = sensor_msgs::msg::PointField::FLOAT32;
164 };
165 
166 template<>
168 {
169  static constexpr auto DATATYPE = sensor_msgs::msg::PointField::FLOAT64;
170 };
171 
172 template<typename T>
173 LIDAR_UTILS_PUBLIC
174 sensor_msgs::msg::PointCloud2::SharedPtr create_custom_pcl(
175  const std::vector<std::string> & field_names,
176  const uint32_t cloud_size)
177 {
179  PointCloud2::SharedPtr msg = std::make_shared<PointCloud2>();
180  const auto field_size = field_names.size();
181  msg->height = 1U;
182  msg->width = cloud_size;
183  msg->fields.resize(field_size);
184  for (uint32_t i = 0U; i < field_size; i++) {
185  msg->fields[i].name = field_names[i];
186  }
187  msg->point_step = 0U;
188  for (uint32_t idx = 0U; idx < field_size; ++idx) {
189  msg->fields[idx].offset = static_cast<uint32_t>(idx * sizeof(T));
190  msg->fields[idx].datatype = _create_custom_pcl_datatype<T>::DATATYPE;
191  msg->fields[idx].count = 1U;
192  msg->point_step += static_cast<uint32_t>(sizeof(T));
193  }
194  const std::size_t capacity = msg->point_step * cloud_size;
195  msg->data.clear();
196  msg->data.reserve(capacity);
197  for (std::size_t i = 0; i < capacity; ++i) {
198  msg->data.emplace_back(0U); // initialize all values equal to 0
199  }
200  msg->row_step = msg->point_step * msg->width;
201  msg->is_bigendian = false;
202  msg->is_dense = false;
203  msg->header.frame_id = "base_link";
204  return msg;
205 }
206 
208 class LIDAR_UTILS_PUBLIC DistanceFilter
209 {
210 public:
214  DistanceFilter(float32_t min_radius, float32_t max_radius);
215  static constexpr auto FEPS = std::numeric_limits<float32_t>::epsilon();
216 
222  template<typename T>
223  bool8_t operator()(const T & pt) const
224  {
226  auto pt_radius = dot_3d(pt, pt);
227  return comp::abs_gte(pt_radius, m_min_r2, FEPS) &&
228  comp::abs_lte(pt_radius, m_max_r2, FEPS);
229  }
230 
231 private:
232  float32_t m_min_r2;
233  float32_t m_max_r2;
234 };
235 
237 class LIDAR_UTILS_PUBLIC StaticTransformer
238 {
239 public:
244 
249  template<typename T>
250  void transform(const T & ref, T & out) const //NOLINT (false positive: this is not std::transform)
251  {
258  Eigen::Vector3f out_mat = m_tf * Eigen::Vector3f{x_(ref), y_(ref), z_(ref)};
259  xr_(out) = out_mat[0];
260  yr_(out) = out_mat[1];
261  zr_(out) = out_mat[2];
262  }
263 
264 private:
265  Eigen::Affine3f m_tf;
266 };
267 
270 class LIDAR_UTILS_PUBLIC AngleFilter
271 {
272 public:
276  AngleFilter(float32_t start_angle, float32_t end_angle);
277 
279  static constexpr float32_t PI = 3.14159265359F;
280  static constexpr auto FEPS = std::numeric_limits<float32_t>::epsilon() * 1e2F;
281 
288  template<typename T>
289  bool8_t operator()(const T & pt) const
290  {
292  bool8_t ret = false;
293 
294  // Squared magnitude of the vector
295  const auto pt_len2 = dot_2d(pt, pt);
296  const auto proj_on_normal = dot_2d(pt, m_range_normal);
297  const auto proj_on_normal2 = proj_on_normal * proj_on_normal;
298  const auto is_proj_negative = (proj_on_normal + FEPS) < 0.0F;
299 
300  // Since the input vector's projection is scaled by the length of itself, the
301  // threshold is also scaled by the length of the input vector to make the comparison possible.
302 
303  // To avoid computing the length using sqrt, the expressions are kept in square form, hence
304  // the following sign checks are made to ensure the correctness of the comparisons in
305  // squared form.
306  if ((!m_threshold_negative) && (!is_proj_negative)) {
307  ret = (proj_on_normal2) >= (pt_len2 * (m_threshold2 - FEPS));
308  } else if (m_threshold_negative && (!is_proj_negative)) {
309  ret = true;
310  } else if ((!m_threshold_negative) && is_proj_negative) {
311  ret = false;
312  } else {
313  ret = (proj_on_normal2) <= (pt_len2 * (m_threshold2 + FEPS));
314  }
315  return ret;
316  }
317 
318 private:
319  VectorT m_range_normal;
320  bool8_t m_threshold_negative;
321  float32_t m_threshold2;
322 };
323 
324 class LIDAR_UTILS_PUBLIC IntensityIteratorWrapper
325 {
326 private:
327  sensor_msgs::PointCloud2ConstIterator<uint8_t> m_intensity_it_uint8;
328  sensor_msgs::PointCloud2ConstIterator<float32_t> m_intensity_it_float32;
329  decltype(sensor_msgs::msg::PointField::datatype) m_intensity_datatype;
330 
331 public:
332  explicit IntensityIteratorWrapper(const PointCloud2 & msg);
333 
334  void next();
335 
336  bool8_t eof();
337 
338  template<typename PointFieldValueT>
339  void get_current_value(PointFieldValueT & point_field_value)
340  {
341  switch (m_intensity_datatype) {
342  case sensor_msgs::msg::PointField::UINT8:
343  point_field_value = *m_intensity_it_uint8;
344  break;
345  case sensor_msgs::msg::PointField::FLOAT32:
346  point_field_value = *m_intensity_it_float32;
347  break;
348  default:
349  throw std::runtime_error(
350  "Intensity type not supported: " +
351  std::to_string(m_intensity_datatype));
352  }
353  }
354 };
355 
356 } // namespace lidar_utils
357 } // namespace common
358 } // namespace autoware
359 
360 #endif // LIDAR_UTILS__POINT_CLOUD_UTILS_HPP_
autoware::common::lidar_utils::IntensityIteratorWrapper
Definition: point_cloud_utils.hpp:324
autoware::common::lidar_utils::DistanceFilter::operator()
bool8_t operator()(const T &pt) const
Check if the point is within the allowed range of the filter. Check is done in square form to avoid s...
Definition: point_cloud_utils.hpp:223
autoware::common::geometry::point_adapter::x_
auto x_(const PointT &pt)
Gets the x value for a point.
Definition: common_2d.hpp:50
autoware::common::lidar_utils::CloudViewRing
point_cloud_msg_wrapper::PointCloud2View< autoware::common::types::PointXYZIF > CloudViewRing
Definition: point_cloud_utils.hpp:58
autoware::common::lidar_utils::MAX_SCAN_POINTS
static const uint32_t MAX_SCAN_POINTS
Definition: point_cloud_utils.hpp:68
autoware::common::lidar_utils::SafeCloudIndices
Definition: point_cloud_utils.hpp:76
types.hpp
This file includes common type definition.
PI
const double PI
Definition: reeds_shepp_impl.cpp:91
autoware::common::helper_functions::comparisons::abs_lte
bool abs_lte(const T &a, const T &b, const T &eps)
Check for approximate less than or equal in absolute terms.
Definition: float_comparisons.hpp:69
autoware::common::lidar_utils::StaticTransformer
Transform to apply a constant transform to given points.
Definition: point_cloud_utils.hpp:237
autoware::common::lidar_utils::IntensityIteratorWrapper::get_current_value
void get_current_value(PointFieldValueT &point_field_value)
Definition: point_cloud_utils.hpp:339
autoware::common::geometry::dot_2d
auto dot_2d(const T1 &pt, const T2 &q)
compute p * q = p1 * q1 + p2 * q2
Definition: common_2d.hpp:193
autoware::common::lidar_utils::CloudModifierRing
point_cloud_msg_wrapper::PointCloud2Modifier< autoware::common::types::PointXYZIF > CloudModifierRing
Definition: point_cloud_utils.hpp:57
autoware::common::types::PointXYZIF
Definition: types.hpp:56
autoware::common::lidar_utils::AngleFilter
Filter class to check if a point's azimuth lies within a range defined by a start and end angles....
Definition: point_cloud_utils.hpp:270
autoware::common::lidar_utils::AngleFilter::operator()
bool8_t operator()(const T &pt) const
Check if a point's azimuth lies in the range [start, end] in counter-clock-wise-direction....
Definition: point_cloud_utils.hpp:289
autoware::common::lidar_utils::DistanceFilter
Filter class to check if a point lies within a range defined by a min and max radius.
Definition: point_cloud_utils.hpp:208
autoware::common::types::bool8_t
bool bool8_t
Definition: types.hpp:39
autoware::common::geometry::dot_3d
auto dot_3d(const T1 &pt, const T2 &q)
compute p * q = p1 * q1 + p2 * q2 + p3 * 13
Definition: common_3d.hpp:37
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::common::lidar_utils::get_cluster
LIDAR_UTILS_PUBLIC std::pair< autoware_auto_perception_msgs::msg::PointClusters::_points_type::iterator, autoware_auto_perception_msgs::msg::PointClusters::_points_type::iterator > get_cluster(autoware_auto_perception_msgs::msg::PointClusters &clusters, const std::size_t cls_id)
Get cluster from clusters based on the cluster id.
Definition: point_cloud_utils.cpp:46
common_3d.hpp
This file includes common functionality for 3D geometry, such as dot products.
autoware::common::lidar_utils::_create_custom_pcl_datatype
Definition: point_cloud_utils.hpp:122
autoware::common::lidar_utils::CloudModifier
point_cloud_msg_wrapper::PointCloud2Modifier< autoware::common::types::PointXYZI > CloudModifier
Definition: point_cloud_utils.hpp:53
autoware::common::lidar_utils::has_intensity_and_throw_if_no_xyz
LIDAR_UTILS_PUBLIC bool8_t has_intensity_and_throw_if_no_xyz(const PointCloud2::SharedPtr &cloud)
Definition: point_cloud_utils.cpp:88
float_comparisons.hpp
autoware::common::geometry::point_adapter::yr_
auto & yr_(PointT &pt)
Gets a reference to the y value for a point.
Definition: common_2d.hpp:114
autoware::common::lidar_utils::index_after_last_safe_byte_index
LIDAR_UTILS_PUBLIC std::size_t index_after_last_safe_byte_index(const sensor_msgs::msg::PointCloud2 &msg) noexcept
Compute minimum safe length of point cloud access.
Definition: point_cloud_utils.cpp:138
motion::planning::recordreplay_planner_nodes::Transform
geometry_msgs::msg::TransformStamped Transform
Definition: recordreplay_planner_node.hpp:56
visibility_control.hpp
autoware::common::helper_functions::comparisons
Definition: bool_comparisons.hpp:32
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:45
autoware::common::lidar_utils::create_custom_pcl
LIDAR_UTILS_PUBLIC sensor_msgs::msg::PointCloud2::SharedPtr create_custom_pcl(const std::vector< std::string > &field_names, const uint32_t cloud_size)
Definition: point_cloud_utils.hpp:174
autoware::common::geometry::point_adapter::xr_
auto & xr_(PointT &pt)
Gets a reference to the x value for a point.
Definition: common_2d.hpp:98
autoware::common::lidar_utils::sanitize_point_cloud
LIDAR_UTILS_PUBLIC SafeCloudIndices sanitize_point_cloud(const sensor_msgs::msg::PointCloud2 &msg)
Definition: point_cloud_utils.cpp:153
autoware::common::lidar_utils::CloudView
point_cloud_msg_wrapper::PointCloud2View< autoware::common::types::PointXYZI > CloudView
Definition: point_cloud_utils.hpp:54
autoware::common::helper_functions::comparisons::abs_gte
bool abs_gte(const T &a, const T &b, const T &eps)
Check for approximate greater than or equal in absolute terms.
Definition: float_comparisons.hpp:80
autoware::common::lidar_utils::SafeCloudIndices::point_step
std::size_t point_step
Definition: point_cloud_utils.hpp:78
autoware::common::lidar_utils::StaticTransformer::transform
void transform(const T &ref, T &out) const
Apply the transform to a point that has the proper point adapters defined.
Definition: point_cloud_utils.hpp:250
autoware::common::geometry::point_adapter::y_
auto y_(const PointT &pt)
Gets the y value for a point.
Definition: common_2d.hpp:66
autoware::common::lidar_utils::SafeCloudIndices::data_length
std::size_t data_length
Definition: point_cloud_utils.hpp:79
autoware::common::types::float64_t
double float64_t
Definition: types.hpp:47
autoware::common::geometry::point_adapter::z_
auto z_(const PointT &pt)
Gets the z value for a point.
Definition: common_2d.hpp:82
autoware::common::geometry::point_adapter::zr_
auto & zr_(PointT &pt)
Gets a reference to the z value for a point.
Definition: common_2d.hpp:130
autoware::motion::motion_common::Vector3f
Eigen::Matrix< float64_t, 3, 1 > Vector3f
Definition: trajectory_common.hpp:42
autoware::perception::filters::filter_node_base::PointCloud2
sensor_msgs::msg::PointCloud2 PointCloud2
Definition: filter_node_base.cpp:32