Go to the documentation of this file.
19 #ifndef LIDAR_UTILS__POINT_CLOUD_UTILS_HPP_
20 #define LIDAR_UTILS__POINT_CLOUD_UTILS_HPP_
24 #include <autoware_auto_perception_msgs/msg/point_clusters.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>
34 #include <Eigen/Geometry>
48 namespace comp = helper_functions::comparisons;
53 point_cloud_msg_wrapper::PointCloud2Modifier<autoware::common::types::PointXYZI>;
54 using CloudView = point_cloud_msg_wrapper::PointCloud2View<autoware::common::types::PointXYZI>;
57 point_cloud_msg_wrapper::PointCloud2Modifier<autoware::common::types::PointXYZIF>;
58 using CloudViewRing = point_cloud_msg_wrapper::PointCloud2View<autoware::common::types::PointXYZIF>;
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);
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);
127 static constexpr
auto DATATYPE = sensor_msgs::msg::PointField::INT8;
133 static constexpr
auto DATATYPE = sensor_msgs::msg::PointField::UINT8;
139 static constexpr
auto DATATYPE = sensor_msgs::msg::PointField::INT16;
145 static constexpr
auto DATATYPE = sensor_msgs::msg::PointField::UINT16;
151 static constexpr
auto DATATYPE = sensor_msgs::msg::PointField::INT32;
157 static constexpr
auto DATATYPE = sensor_msgs::msg::PointField::UINT32;
163 static constexpr
auto DATATYPE = sensor_msgs::msg::PointField::FLOAT32;
169 static constexpr
auto DATATYPE = sensor_msgs::msg::PointField::FLOAT64;
175 const std::vector<std::string> & field_names,
176 const uint32_t cloud_size)
179 PointCloud2::SharedPtr msg = std::make_shared<PointCloud2>();
180 const auto field_size = field_names.size();
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];
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));
191 msg->fields[idx].count = 1U;
192 msg->point_step +=
static_cast<uint32_t
>(
sizeof(T));
194 const std::size_t capacity = msg->point_step * cloud_size;
196 msg->data.reserve(capacity);
197 for (std::size_t i = 0; i < capacity; ++i) {
198 msg->data.emplace_back(0U);
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";
215 static constexpr
auto FEPS = std::numeric_limits<float32_t>::epsilon();
226 auto pt_radius =
dot_3d(pt, pt);
259 xr_(out) = out_mat[0];
260 yr_(out) = out_mat[1];
261 zr_(out) = out_mat[2];
265 Eigen::Affine3f m_tf;
280 static constexpr
auto FEPS = std::numeric_limits<float32_t>::epsilon() * 1e2F;
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;
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)) {
310 }
else if ((!m_threshold_negative) && is_proj_negative) {
313 ret = (proj_on_normal2) <= (pt_len2 * (m_threshold2 + FEPS));
319 VectorT m_range_normal;
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;
338 template<
typename Po
intFieldValueT>
341 switch (m_intensity_datatype) {
342 case sensor_msgs::msg::PointField::UINT8:
343 point_field_value = *m_intensity_it_uint8;
345 case sensor_msgs::msg::PointField::FLOAT32:
346 point_field_value = *m_intensity_it_float32;
349 throw std::runtime_error(
350 "Intensity type not supported: " +
351 std::to_string(m_intensity_datatype));
360 #endif // LIDAR_UTILS__POINT_CLOUD_UTILS_HPP_
Definition: point_cloud_utils.hpp:324
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
auto x_(const PointT &pt)
Gets the x value for a point.
Definition: common_2d.hpp:50
point_cloud_msg_wrapper::PointCloud2View< autoware::common::types::PointXYZIF > CloudViewRing
Definition: point_cloud_utils.hpp:58
static const uint32_t MAX_SCAN_POINTS
Definition: point_cloud_utils.hpp:68
Definition: point_cloud_utils.hpp:76
This file includes common type definition.
const double PI
Definition: reeds_shepp_impl.cpp:91
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
void get_current_value(PointFieldValueT &point_field_value)
Definition: point_cloud_utils.hpp:339
auto dot_2d(const T1 &pt, const T2 &q)
compute p * q = p1 * q1 + p2 * q2
Definition: common_2d.hpp:193
point_cloud_msg_wrapper::PointCloud2Modifier< autoware::common::types::PointXYZIF > CloudModifierRing
Definition: point_cloud_utils.hpp:57
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
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
Filter class to check if a point lies within a range defined by a min and max radius.
Definition: point_cloud_utils.hpp:208
bool bool8_t
Definition: types.hpp:39
auto dot_3d(const T1 &pt, const T2 &q)
compute p * q = p1 * q1 + p2 * q2 + p3 * 13
Definition: common_3d.hpp:37
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
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
This file includes common functionality for 3D geometry, such as dot products.
Definition: point_cloud_utils.hpp:122
point_cloud_msg_wrapper::PointCloud2Modifier< autoware::common::types::PointXYZI > CloudModifier
Definition: point_cloud_utils.hpp:53
LIDAR_UTILS_PUBLIC bool8_t has_intensity_and_throw_if_no_xyz(const PointCloud2::SharedPtr &cloud)
Definition: point_cloud_utils.cpp:88
auto & yr_(PointT &pt)
Gets a reference to the y value for a point.
Definition: common_2d.hpp:114
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
geometry_msgs::msg::TransformStamped Transform
Definition: recordreplay_planner_node.hpp:56
Definition: bool_comparisons.hpp:32
float float32_t
Definition: types.hpp:45
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
auto & xr_(PointT &pt)
Gets a reference to the x value for a point.
Definition: common_2d.hpp:98
LIDAR_UTILS_PUBLIC SafeCloudIndices sanitize_point_cloud(const sensor_msgs::msg::PointCloud2 &msg)
Definition: point_cloud_utils.cpp:153
point_cloud_msg_wrapper::PointCloud2View< autoware::common::types::PointXYZI > CloudView
Definition: point_cloud_utils.hpp:54
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
std::size_t point_step
Definition: point_cloud_utils.hpp:78
auto y_(const PointT &pt)
Gets the y value for a point.
Definition: common_2d.hpp:66
std::size_t data_length
Definition: point_cloud_utils.hpp:79
double float64_t
Definition: types.hpp:47
auto z_(const PointT &pt)
Gets the z value for a point.
Definition: common_2d.hpp:82
auto & zr_(PointT &pt)
Gets a reference to the z value for a point.
Definition: common_2d.hpp:130
Eigen::Matrix< float64_t, 3, 1 > Vector3f
Definition: trajectory_common.hpp:42
sensor_msgs::msg::PointCloud2 PointCloud2
Definition: filter_node_base.cpp:32