Skip to content

Commit 917f723

Browse files
committed
Revert "feat(lidar_centerpoint): accelerated preprocessing for centerpoint (autowarefoundation#6989)"
This reverts commit fffb149.
1 parent 60b05b0 commit 917f723

33 files changed

+173
-491
lines changed

perception/image_projection_based_fusion/CMakeLists.txt

-1
Original file line numberDiff line numberDiff line change
@@ -127,7 +127,6 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL)
127127

128128
ament_auto_add_library(pointpainting_lib SHARED
129129
src/pointpainting_fusion/node.cpp
130-
src/pointpainting_fusion/pointcloud_densification.cpp
131130
src/pointpainting_fusion/pointpainting_trt.cpp
132131
src/pointpainting_fusion/voxel_generator.cpp
133132
)

perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/pointcloud_densification.hpp

-72
This file was deleted.

perception/image_projection_based_fusion/include/image_projection_based_fusion/pointpainting_fusion/voxel_generator.hpp

100644100755
+3-19
Original file line numberDiff line numberDiff line change
@@ -15,35 +15,19 @@
1515
#ifndef IMAGE_PROJECTION_BASED_FUSION__POINTPAINTING_FUSION__VOXEL_GENERATOR_HPP_
1616
#define IMAGE_PROJECTION_BASED_FUSION__POINTPAINTING_FUSION__VOXEL_GENERATOR_HPP_
1717

18-
#include <image_projection_based_fusion/pointpainting_fusion/pointcloud_densification.hpp>
19-
#include <lidar_centerpoint/preprocess/pointcloud_densification.hpp>
2018
#include <lidar_centerpoint/preprocess/voxel_generator.hpp>
2119

2220
#include <bitset>
23-
#include <memory>
2421
#include <vector>
2522

2623
namespace image_projection_based_fusion
2724
{
28-
29-
class VoxelGenerator
25+
class VoxelGenerator : public centerpoint::VoxelGenerator
3026
{
3127
public:
32-
explicit VoxelGenerator(
33-
const centerpoint::DensificationParam & param, const centerpoint::CenterPointConfig & config);
34-
35-
bool enqueuePointCloud(
36-
const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer);
37-
38-
std::size_t generateSweepPoints(std::vector<float> & points);
39-
40-
protected:
41-
std::unique_ptr<PointCloudDensification> pd_ptr_{nullptr};
28+
using centerpoint::VoxelGenerator::VoxelGenerator;
4229

43-
centerpoint::CenterPointConfig config_;
44-
std::array<float, 6> range_;
45-
std::array<int, 3> grid_size_;
46-
std::array<float, 3> recip_voxel_size_;
30+
std::size_t generateSweepPoints(std::vector<float> & points) override;
4731
};
4832
} // namespace image_projection_based_fusion
4933

perception/image_projection_based_fusion/src/pointpainting_fusion/pointcloud_densification.cpp

-103
This file was deleted.

perception/image_projection_based_fusion/src/pointpainting_fusion/voxel_generator.cpp

-26
Original file line numberDiff line numberDiff line change
@@ -18,32 +18,6 @@
1818

1919
namespace image_projection_based_fusion
2020
{
21-
22-
VoxelGenerator::VoxelGenerator(
23-
const centerpoint::DensificationParam & param, const centerpoint::CenterPointConfig & config)
24-
: config_(config)
25-
{
26-
pd_ptr_ = std::make_unique<PointCloudDensification>(param);
27-
range_[0] = config.range_min_x_;
28-
range_[1] = config.range_min_y_;
29-
range_[2] = config.range_min_z_;
30-
range_[3] = config.range_max_x_;
31-
range_[4] = config.range_max_y_;
32-
range_[5] = config.range_max_z_;
33-
grid_size_[0] = config.grid_size_x_;
34-
grid_size_[1] = config.grid_size_y_;
35-
grid_size_[2] = config.grid_size_z_;
36-
recip_voxel_size_[0] = 1 / config.voxel_size_x_;
37-
recip_voxel_size_[1] = 1 / config.voxel_size_y_;
38-
recip_voxel_size_[2] = 1 / config.voxel_size_z_;
39-
}
40-
41-
bool VoxelGenerator::enqueuePointCloud(
42-
const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer)
43-
{
44-
return pd_ptr_->enqueuePointCloud(input_pointcloud_msg, tf_buffer);
45-
}
46-
4721
size_t VoxelGenerator::generateSweepPoints(std::vector<float> & points)
4822
{
4923
Eigen::Vector3f point_current, point_past;

perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_trt.hpp

+9-8
Original file line numberDiff line numberDiff line change
@@ -15,14 +15,15 @@
1515
#ifndef LIDAR_CENTERPOINT__CENTERPOINT_TRT_HPP_
1616
#define LIDAR_CENTERPOINT__CENTERPOINT_TRT_HPP_
1717

18-
#include "lidar_centerpoint/cuda_utils.hpp"
19-
#include "lidar_centerpoint/network/network_trt.hpp"
20-
#include "lidar_centerpoint/postprocess/postprocess_kernel.hpp"
21-
#include "lidar_centerpoint/preprocess/voxel_generator.hpp"
22-
#include "pcl/point_cloud.h"
23-
#include "pcl/point_types.h"
24-
25-
#include "sensor_msgs/msg/point_cloud2.hpp"
18+
#include <lidar_centerpoint/cuda_utils.hpp>
19+
#include <lidar_centerpoint/network/network_trt.hpp>
20+
#include <lidar_centerpoint/postprocess/postprocess_kernel.hpp>
21+
#include <lidar_centerpoint/preprocess/voxel_generator.hpp>
22+
23+
#include <sensor_msgs/msg/point_cloud2.hpp>
24+
25+
#include <pcl/point_cloud.h>
26+
#include <pcl/point_types.h>
2627

2728
#include <memory>
2829
#include <string>

perception/lidar_centerpoint/include/lidar_centerpoint/cuda_utils.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,7 @@
4242
#ifndef LIDAR_CENTERPOINT__CUDA_UTILS_HPP_
4343
#define LIDAR_CENTERPOINT__CUDA_UTILS_HPP_
4444

45-
#include "cuda_runtime_api.h"
45+
#include <cuda_runtime_api.h>
4646

4747
#include <memory>
4848
#include <sstream>

perception/lidar_centerpoint/include/lidar_centerpoint/detection_class_remapper.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -17,10 +17,10 @@
1717

1818
#include <Eigen/Core>
1919

20-
#include "autoware_perception_msgs/msg/detected_object_kinematics.hpp"
21-
#include "autoware_perception_msgs/msg/detected_objects.hpp"
22-
#include "autoware_perception_msgs/msg/object_classification.hpp"
23-
#include "autoware_perception_msgs/msg/shape.hpp"
20+
#include <autoware_perception_msgs/msg/detected_object_kinematics.hpp>
21+
#include <autoware_perception_msgs/msg/detected_objects.hpp>
22+
#include <autoware_perception_msgs/msg/object_classification.hpp>
23+
#include <autoware_perception_msgs/msg/shape.hpp>
2424

2525
#include <vector>
2626

perception/lidar_centerpoint/include/lidar_centerpoint/network/network_trt.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -15,8 +15,8 @@
1515
#ifndef LIDAR_CENTERPOINT__NETWORK__NETWORK_TRT_HPP_
1616
#define LIDAR_CENTERPOINT__NETWORK__NETWORK_TRT_HPP_
1717

18-
#include "lidar_centerpoint/centerpoint_config.hpp"
19-
#include "lidar_centerpoint/network/tensorrt_wrapper.hpp"
18+
#include <lidar_centerpoint/centerpoint_config.hpp>
19+
#include <lidar_centerpoint/network/tensorrt_wrapper.hpp>
2020

2121
#include <vector>
2222

perception/lidar_centerpoint/include/lidar_centerpoint/network/scatter_kernel.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -15,8 +15,8 @@
1515
#ifndef LIDAR_CENTERPOINT__NETWORK__SCATTER_KERNEL_HPP_
1616
#define LIDAR_CENTERPOINT__NETWORK__SCATTER_KERNEL_HPP_
1717

18-
#include "cuda.h"
19-
#include "cuda_runtime_api.h"
18+
#include <cuda.h>
19+
#include <cuda_runtime_api.h>
2020

2121
namespace centerpoint
2222
{

perception/lidar_centerpoint/include/lidar_centerpoint/network/tensorrt_wrapper.hpp

+5-4
Original file line numberDiff line numberDiff line change
@@ -15,9 +15,10 @@
1515
#ifndef LIDAR_CENTERPOINT__NETWORK__TENSORRT_WRAPPER_HPP_
1616
#define LIDAR_CENTERPOINT__NETWORK__TENSORRT_WRAPPER_HPP_
1717

18-
#include "NvInfer.h"
19-
#include "lidar_centerpoint/centerpoint_config.hpp"
20-
#include "tensorrt_common/tensorrt_common.hpp"
18+
#include <lidar_centerpoint/centerpoint_config.hpp>
19+
#include <tensorrt_common/tensorrt_common.hpp>
20+
21+
#include <NvInfer.h>
2122

2223
#include <iostream>
2324
#include <memory>
@@ -31,7 +32,7 @@ class TensorRTWrapper
3132
public:
3233
explicit TensorRTWrapper(const CenterPointConfig & config);
3334

34-
virtual ~TensorRTWrapper();
35+
~TensorRTWrapper();
3536

3637
bool init(
3738
const std::string & onnx_path, const std::string & engine_path, const std::string & precision);

perception/lidar_centerpoint/include/lidar_centerpoint/node.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -15,13 +15,13 @@
1515
#ifndef LIDAR_CENTERPOINT__NODE_HPP_
1616
#define LIDAR_CENTERPOINT__NODE_HPP_
1717

18-
#include "lidar_centerpoint/centerpoint_trt.hpp"
19-
#include "lidar_centerpoint/detection_class_remapper.hpp"
2018
#include "lidar_centerpoint/postprocess/non_maximum_suppression.hpp"
2119

2220
#include <autoware/universe_utils/ros/debug_publisher.hpp>
2321
#include <autoware/universe_utils/ros/published_time_publisher.hpp>
2422
#include <autoware/universe_utils/system/stop_watch.hpp>
23+
#include <lidar_centerpoint/centerpoint_trt.hpp>
24+
#include <lidar_centerpoint/detection_class_remapper.hpp>
2525
#include <rclcpp/rclcpp.hpp>
2626

2727
#include <autoware_perception_msgs/msg/detected_object_kinematics.hpp>

perception/lidar_centerpoint/include/lidar_centerpoint/postprocess/circle_nms_kernel.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -15,8 +15,9 @@
1515
#ifndef LIDAR_CENTERPOINT__POSTPROCESS__CIRCLE_NMS_KERNEL_HPP_
1616
#define LIDAR_CENTERPOINT__POSTPROCESS__CIRCLE_NMS_KERNEL_HPP_
1717

18-
#include "lidar_centerpoint/utils.hpp"
19-
#include "thrust/device_vector.h"
18+
#include <lidar_centerpoint/utils.hpp>
19+
20+
#include <thrust/device_vector.h>
2021

2122
namespace centerpoint
2223
{

perception/lidar_centerpoint/include/lidar_centerpoint/postprocess/postprocess_kernel.hpp

+6-5
Original file line numberDiff line numberDiff line change
@@ -15,11 +15,12 @@
1515
#ifndef LIDAR_CENTERPOINT__POSTPROCESS__POSTPROCESS_KERNEL_HPP_
1616
#define LIDAR_CENTERPOINT__POSTPROCESS__POSTPROCESS_KERNEL_HPP_
1717

18-
#include "cuda.h"
19-
#include "cuda_runtime_api.h"
20-
#include "lidar_centerpoint/centerpoint_config.hpp"
21-
#include "lidar_centerpoint/utils.hpp"
22-
#include "thrust/device_vector.h"
18+
#include <lidar_centerpoint/centerpoint_config.hpp>
19+
#include <lidar_centerpoint/utils.hpp>
20+
21+
#include <cuda.h>
22+
#include <cuda_runtime_api.h>
23+
#include <thrust/device_vector.h>
2324

2425
#include <vector>
2526

0 commit comments

Comments
 (0)