Autoware.Auto
point_cloud_utils.hpp File Reference

This class defines common functions and classes to work with pointclouds. More...

#include <lidar_utils/visibility_control.hpp>
#include <autoware_auto_perception_msgs/msg/point_clusters.hpp>
#include <common/types.hpp>
#include <geometry/common_3d.hpp>
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <helper_functions/float_comparisons.hpp>
#include <point_cloud_msg_wrapper/point_cloud_msg_wrapper.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <sensor_msgs/point_cloud2_iterator.hpp>
#include <Eigen/Core>
#include <Eigen/Geometry>
#include <atomic>
#include <limits>
#include <memory>
#include <string>
#include <utility>
#include <vector>
Include dependency graph for point_cloud_utils.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  autoware::common::lidar_utils::SafeCloudIndices
 
struct  autoware::common::lidar_utils::_create_custom_pcl_datatype< T >
 
struct  autoware::common::lidar_utils::_create_custom_pcl_datatype< int8_t >
 
struct  autoware::common::lidar_utils::_create_custom_pcl_datatype< uint8_t >
 
struct  autoware::common::lidar_utils::_create_custom_pcl_datatype< int16_t >
 
struct  autoware::common::lidar_utils::_create_custom_pcl_datatype< uint16_t >
 
struct  autoware::common::lidar_utils::_create_custom_pcl_datatype< int32_t >
 
struct  autoware::common::lidar_utils::_create_custom_pcl_datatype< uint32_t >
 
struct  autoware::common::lidar_utils::_create_custom_pcl_datatype< float32_t >
 
struct  autoware::common::lidar_utils::_create_custom_pcl_datatype< float64_t >
 
class  autoware::common::lidar_utils::DistanceFilter
 Filter class to check if a point lies within a range defined by a min and max radius. More...
 
class  autoware::common::lidar_utils::StaticTransformer
 Transform to apply a constant transform to given points. More...
 
class  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. The range is defined from start to the end angles in counter-clock-wise direction. More...
 
class  autoware::common::lidar_utils::IntensityIteratorWrapper
 

Namespaces

 autoware
 This file defines the lanelet2_map_provider_node class.
 
 autoware::common
 
 autoware::common::lidar_utils
 

Typedefs

using autoware::common::lidar_utils::CloudModifier = point_cloud_msg_wrapper::PointCloud2Modifier< autoware::common::types::PointXYZI >
 
using autoware::common::lidar_utils::CloudView = point_cloud_msg_wrapper::PointCloud2View< autoware::common::types::PointXYZI >
 
using autoware::common::lidar_utils::CloudModifierRing = point_cloud_msg_wrapper::PointCloud2Modifier< autoware::common::types::PointXYZIF >
 
using autoware::common::lidar_utils::CloudViewRing = point_cloud_msg_wrapper::PointCloud2View< autoware::common::types::PointXYZIF >
 

Functions

LIDAR_UTILS_PUBLIC std::size_t autoware::common::lidar_utils::index_after_last_safe_byte_index (const sensor_msgs::msg::PointCloud2 &msg) noexcept
 Compute minimum safe length of point cloud access. More...
 
LIDAR_UTILS_PUBLIC SafeCloudIndices autoware::common::lidar_utils::sanitize_point_cloud (const sensor_msgs::msg::PointCloud2 &msg)
 
LIDAR_UTILS_PUBLIC std::pair< autoware_auto_perception_msgs::msg::PointClusters::_points_type::iterator, autoware_auto_perception_msgs::msg::PointClusters::_points_type::iterator > autoware::common::lidar_utils::get_cluster (autoware_auto_perception_msgs::msg::PointClusters &clusters, const std::size_t cls_id)
 Get cluster from clusters based on the cluster id. More...
 
LIDAR_UTILS_PUBLIC std::pair< autoware_auto_perception_msgs::msg::PointClusters::_points_type::const_iterator, autoware_auto_perception_msgs::msg::PointClusters::_points_type::const_iterator > autoware::common::lidar_utils::get_cluster (const autoware_auto_perception_msgs::msg::PointClusters &clusters, const std::size_t cls_id)
 Get cluster from clusters based on the cluster id. More...
 
LIDAR_UTILS_PUBLIC bool8_t autoware::common::lidar_utils::has_intensity_and_throw_if_no_xyz (const PointCloud2::SharedPtr &cloud)
 
LIDAR_UTILS_PUBLIC bool8_t autoware::common::lidar_utils::has_intensity_and_throw_if_no_xyz (const PointCloud2 &cloud)
 
template<typename T >
LIDAR_UTILS_PUBLIC sensor_msgs::msg::PointCloud2::SharedPtr autoware::common::lidar_utils::create_custom_pcl (const std::vector< std::string > &field_names, const uint32_t cloud_size)
 

Variables

static const uint32_t autoware::common::lidar_utils::MAX_SCAN_POINTS = 57872U
 

Detailed Description

This class defines common functions and classes to work with pointclouds.