|
| 1 | +// Copyright 2025 TIER IV, Inc. |
| 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 | +#ifndef AUTOWARE__CUDA_POINTCLOUD_PREPROCESSOR__CUDA_POINTCLOUD_PREPROCESSOR_HPP_ |
| 16 | +#define AUTOWARE__CUDA_POINTCLOUD_PREPROCESSOR__CUDA_POINTCLOUD_PREPROCESSOR_HPP_ |
| 17 | + |
| 18 | +#include "autoware/cuda_pointcloud_preprocessor/point_types.hpp" |
| 19 | +#include "autoware/cuda_pointcloud_preprocessor/types.hpp" |
| 20 | + |
| 21 | +#include <Eigen/Core> |
| 22 | +#include <Eigen/Geometry> |
| 23 | +#include <cuda_blackboard/cuda_pointcloud2.hpp> |
| 24 | + |
| 25 | +#include <geometry_msgs/msg/transform_stamped.hpp> |
| 26 | +#include <geometry_msgs/msg/twist_with_covariance_stamped.hpp> |
| 27 | +#include <geometry_msgs/msg/vector3_stamped.hpp> |
| 28 | +#include <sensor_msgs/msg/point_cloud2.hpp> |
| 29 | + |
| 30 | +#include <thrust/device_vector.h> |
| 31 | + |
| 32 | +#include <cstdint> |
| 33 | +#include <deque> |
| 34 | +#include <memory> |
| 35 | +#include <vector> |
| 36 | + |
| 37 | +namespace autoware::cuda_pointcloud_preprocessor |
| 38 | +{ |
| 39 | + |
| 40 | +class CudaPointcloudPreprocessor |
| 41 | +{ |
| 42 | +public: |
| 43 | + enum class UndistortionType { Invalid, Undistortion2D, Undistortion3D }; |
| 44 | + |
| 45 | + CudaPointcloudPreprocessor(); |
| 46 | + ~CudaPointcloudPreprocessor() = default; |
| 47 | + |
| 48 | + void setCropBoxParameters(const std::vector<CropBoxParameters> & crop_box_parameters); |
| 49 | + void setRingOutlierFilterParameters(const RingOutlierFilterParameters & ring_outlier_parameters); |
| 50 | + void setUndistortionType(const UndistortionType & undistortion_type); |
| 51 | + |
| 52 | + void preallocateOutput(); |
| 53 | + |
| 54 | + std::unique_ptr<cuda_blackboard::CudaPointCloud2> process( |
| 55 | + const sensor_msgs::msg::PointCloud2::ConstSharedPtr input_pointcloud_msg_ptr, |
| 56 | + const geometry_msgs::msg::TransformStamped & transform_msg, |
| 57 | + const std::deque<geometry_msgs::msg::TwistWithCovarianceStamped> & twist_queue, |
| 58 | + const std::deque<geometry_msgs::msg::Vector3Stamped> & angular_velocity_queue, |
| 59 | + const std::uint32_t first_point_rel_stamp_nsec); |
| 60 | + |
| 61 | +private: |
| 62 | + void organizePointcloud(); |
| 63 | + |
| 64 | + CropBoxParameters self_crop_box_parameters_{}; |
| 65 | + CropBoxParameters mirror_crop_box_parameters_{}; |
| 66 | + RingOutlierFilterParameters ring_outlier_parameters_{}; |
| 67 | + UndistortionType undistortion_type_{UndistortionType::Invalid}; |
| 68 | + |
| 69 | + int num_rings_{}; |
| 70 | + int max_points_per_ring_{}; |
| 71 | + std::size_t num_raw_points_{}; |
| 72 | + std::size_t num_organized_points_{}; |
| 73 | + |
| 74 | + std::vector<sensor_msgs::msg::PointField> point_fields_{}; |
| 75 | + std::unique_ptr<cuda_blackboard::CudaPointCloud2> output_pointcloud_ptr_{}; |
| 76 | + |
| 77 | + cudaStream_t stream_; |
| 78 | + int max_blocks_per_grid_{}; |
| 79 | + const int threads_per_block_{256}; |
| 80 | + cudaMemPool_t device_memory_pool_; |
| 81 | + |
| 82 | + // Organizing buffers |
| 83 | + thrust::device_vector<InputPointType> device_input_points_; |
| 84 | + thrust::device_vector<InputPointType> device_organized_points_; |
| 85 | + thrust::device_vector<std::int32_t> device_ring_index_; |
| 86 | + thrust::device_vector<std::uint32_t> device_indexes_tensor_; |
| 87 | + thrust::device_vector<std::uint32_t> device_sorted_indexes_tensor_; |
| 88 | + thrust::device_vector<std::int32_t> device_segment_offsets_; |
| 89 | + thrust::device_vector<std::int32_t> device_max_ring_; |
| 90 | + thrust::device_vector<std::int32_t> device_max_points_per_ring_; |
| 91 | + |
| 92 | + thrust::device_vector<std::uint8_t> device_sort_workspace_; |
| 93 | + std::size_t sort_workspace_bytes_{0}; |
| 94 | + |
| 95 | + // Pointcloud preprocessing buffers |
| 96 | + thrust::device_vector<InputPointType> device_transformed_points_{}; |
| 97 | + thrust::device_vector<OutputPointType> device_output_points_{}; |
| 98 | + thrust::device_vector<std::uint32_t> device_crop_mask_{}; |
| 99 | + thrust::device_vector<std::uint32_t> device_ring_outlier_mask_{}; |
| 100 | + thrust::device_vector<std::uint32_t> device_indices_{}; |
| 101 | + thrust::device_vector<TwistStruct2D> device_twist_2d_structs_{}; |
| 102 | + thrust::device_vector<TwistStruct3D> device_twist_3d_structs_{}; |
| 103 | + thrust::device_vector<CropBoxParameters> host_crop_box_structs_{}; |
| 104 | + thrust::device_vector<CropBoxParameters> device_crop_box_structs_{}; |
| 105 | +}; |
| 106 | + |
| 107 | +} // namespace autoware::cuda_pointcloud_preprocessor |
| 108 | + |
| 109 | +#endif // AUTOWARE__CUDA_POINTCLOUD_PREPROCESSOR__CUDA_POINTCLOUD_PREPROCESSOR_HPP_ |
0 commit comments