Skip to content

Commit fffb149

Browse files
knzo25kminoda
andauthoredJun 20, 2024
feat(lidar_centerpoint): accelerated preprocessing for centerpoint (#6989)
* feat: accelerated preprocessing for centerpoint Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: changed includes to quotes instead of brackets Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: fixed variable name Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * fix: addressed the case where the points in the cache is over the maximum capacity Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * fix: fixed the offset of the output buffer in the kernel Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: reimplemented old logic in the pointpainting package since the new centerpoint logic is incompatible Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * fix: eigen matrices are column major by default. this commit fixes the code that assumed row-major, implements check for data layout, and updates tests Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: fixed missing virtual destructor Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> --------- Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com>
1 parent 8dcddae commit fffb149

33 files changed

+491
-173
lines changed
 

‎perception/image_projection_based_fusion/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -127,6 +127,7 @@ 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
130131
src/pointpainting_fusion/pointpainting_trt.cpp
131132
src/pointpainting_fusion/voxel_generator.cpp
132133
)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,72 @@
1+
// Copyright 2024 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 IMAGE_PROJECTION_BASED_FUSION__POINTPAINTING_FUSION__POINTCLOUD_DENSIFICATION_HPP_
16+
#define IMAGE_PROJECTION_BASED_FUSION__POINTPAINTING_FUSION__POINTCLOUD_DENSIFICATION_HPP_
17+
18+
#include <tf2_ros/buffer.h>
19+
#include <tf2_ros/transform_listener.h>
20+
#ifdef ROS_DISTRO_GALACTIC
21+
#include <tf2_sensor_msgs/tf2_sensor_msgs.h>
22+
#else
23+
#include <tf2_sensor_msgs/tf2_sensor_msgs.hpp>
24+
#endif
25+
26+
#include <lidar_centerpoint/preprocess/pointcloud_densification.hpp>
27+
28+
#include <list>
29+
#include <string>
30+
#include <utility>
31+
32+
namespace image_projection_based_fusion
33+
{
34+
struct PointCloudWithTransform
35+
{
36+
sensor_msgs::msg::PointCloud2 pointcloud_msg;
37+
Eigen::Affine3f affine_past2world;
38+
};
39+
40+
class PointCloudDensification
41+
{
42+
public:
43+
explicit PointCloudDensification(const centerpoint::DensificationParam & param);
44+
45+
bool enqueuePointCloud(
46+
const sensor_msgs::msg::PointCloud2 & input_pointcloud_msg, const tf2_ros::Buffer & tf_buffer);
47+
48+
double getCurrentTimestamp() const { return current_timestamp_; }
49+
Eigen::Affine3f getAffineWorldToCurrent() const { return affine_world2current_; }
50+
std::list<PointCloudWithTransform>::iterator getPointCloudCacheIter()
51+
{
52+
return pointcloud_cache_.begin();
53+
}
54+
bool isCacheEnd(std::list<PointCloudWithTransform>::iterator iter)
55+
{
56+
return iter == pointcloud_cache_.end();
57+
}
58+
unsigned int pointcloud_cache_size() const { return param_.pointcloud_cache_size(); }
59+
60+
private:
61+
void enqueue(const sensor_msgs::msg::PointCloud2 & msg, const Eigen::Affine3f & affine);
62+
void dequeue();
63+
64+
centerpoint::DensificationParam param_;
65+
double current_timestamp_{0.0};
66+
Eigen::Affine3f affine_world2current_;
67+
std::list<PointCloudWithTransform> pointcloud_cache_;
68+
};
69+
70+
} // namespace image_projection_based_fusion
71+
72+
#endif // IMAGE_PROJECTION_BASED_FUSION__POINTPAINTING_FUSION__POINTCLOUD_DENSIFICATION_HPP_

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

100755100644
+19-3
Original file line numberDiff line numberDiff line change
@@ -15,19 +15,35 @@
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>
1820
#include <lidar_centerpoint/preprocess/voxel_generator.hpp>
1921

2022
#include <bitset>
23+
#include <memory>
2124
#include <vector>
2225

2326
namespace image_projection_based_fusion
2427
{
25-
class VoxelGenerator : public centerpoint::VoxelGenerator
28+
29+
class VoxelGenerator
2630
{
2731
public:
28-
using centerpoint::VoxelGenerator::VoxelGenerator;
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};
2942

30-
std::size_t generateSweepPoints(std::vector<float> & points) override;
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_;
3147
};
3248
} // namespace image_projection_based_fusion
3349

Original file line numberDiff line numberDiff line change
@@ -0,0 +1,103 @@
1+
// Copyright 2024 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+
#include "image_projection_based_fusion/pointpainting_fusion/pointcloud_densification.hpp"
16+
17+
#include <pcl_ros/transforms.hpp>
18+
19+
#include <boost/optional.hpp>
20+
21+
#include <pcl_conversions/pcl_conversions.h>
22+
#ifdef ROS_DISTRO_GALACTIC
23+
#include <tf2_eigen/tf2_eigen.h>
24+
#else
25+
#include <tf2_eigen/tf2_eigen.hpp>
26+
#endif
27+
28+
#include <string>
29+
#include <utility>
30+
31+
namespace
32+
{
33+
boost::optional<geometry_msgs::msg::Transform> getTransform(
34+
const tf2_ros::Buffer & tf_buffer, const std::string & target_frame_id,
35+
const std::string & source_frame_id, const rclcpp::Time & time)
36+
{
37+
try {
38+
geometry_msgs::msg::TransformStamped transform_stamped;
39+
transform_stamped = tf_buffer.lookupTransform(
40+
target_frame_id, source_frame_id, time, rclcpp::Duration::from_seconds(0.5));
41+
return transform_stamped.transform;
42+
} catch (tf2::TransformException & ex) {
43+
RCLCPP_WARN_STREAM(rclcpp::get_logger("lidar_centerpoint"), ex.what());
44+
return boost::none;
45+
}
46+
}
47+
48+
Eigen::Affine3f transformToEigen(const geometry_msgs::msg::Transform & t)
49+
{
50+
Eigen::Affine3f a;
51+
a.matrix() = tf2::transformToEigen(t).matrix().cast<float>();
52+
return a;
53+
}
54+
55+
} // namespace
56+
57+
namespace image_projection_based_fusion
58+
{
59+
PointCloudDensification::PointCloudDensification(const centerpoint::DensificationParam & param)
60+
: param_(param)
61+
{
62+
}
63+
64+
bool PointCloudDensification::enqueuePointCloud(
65+
const sensor_msgs::msg::PointCloud2 & pointcloud_msg, const tf2_ros::Buffer & tf_buffer)
66+
{
67+
const auto header = pointcloud_msg.header;
68+
69+
if (param_.pointcloud_cache_size() > 1) {
70+
auto transform_world2current =
71+
getTransform(tf_buffer, header.frame_id, param_.world_frame_id(), header.stamp);
72+
if (!transform_world2current) {
73+
return false;
74+
}
75+
auto affine_world2current = transformToEigen(transform_world2current.get());
76+
77+
enqueue(pointcloud_msg, affine_world2current);
78+
} else {
79+
enqueue(pointcloud_msg, Eigen::Affine3f::Identity());
80+
}
81+
82+
dequeue();
83+
84+
return true;
85+
}
86+
87+
void PointCloudDensification::enqueue(
88+
const sensor_msgs::msg::PointCloud2 & msg, const Eigen::Affine3f & affine_world2current)
89+
{
90+
affine_world2current_ = affine_world2current;
91+
current_timestamp_ = rclcpp::Time(msg.header.stamp).seconds();
92+
PointCloudWithTransform pointcloud = {msg, affine_world2current.inverse()};
93+
pointcloud_cache_.push_front(pointcloud);
94+
}
95+
96+
void PointCloudDensification::dequeue()
97+
{
98+
if (pointcloud_cache_.size() > param_.pointcloud_cache_size()) {
99+
pointcloud_cache_.pop_back();
100+
}
101+
}
102+
103+
} // namespace image_projection_based_fusion

‎perception/image_projection_based_fusion/src/pointpainting_fusion/voxel_generator.cpp

+26
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,32 @@
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+
2147
size_t VoxelGenerator::generateSweepPoints(std::vector<float> & points)
2248
{
2349
Eigen::Vector3f point_current, point_past;

‎perception/lidar_centerpoint/include/lidar_centerpoint/centerpoint_trt.hpp

+8-9
Original file line numberDiff line numberDiff line change
@@ -15,15 +15,14 @@
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-
23-
#include <sensor_msgs/msg/point_cloud2.hpp>
24-
25-
#include <pcl/point_cloud.h>
26-
#include <pcl/point_types.h>
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"
2726

2827
#include <memory>
2928
#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

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

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

2322
#include <iostream>
2423
#include <memory>
@@ -32,7 +31,7 @@ class TensorRTWrapper
3231
public:
3332
explicit TensorRTWrapper(const CenterPointConfig & config);
3433

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

3736
bool init(
3837
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"
1820
#include "lidar_centerpoint/postprocess/non_maximum_suppression.hpp"
1921

2022
#include <autoware/universe_utils/ros/debug_publisher.hpp>
2123
#include <autoware/universe_utils/ros/published_time_publisher.hpp>
2224
#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

+2-3
Original file line numberDiff line numberDiff line change
@@ -15,9 +15,8 @@
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-
20-
#include <thrust/device_vector.h>
18+
#include "lidar_centerpoint/utils.hpp"
19+
#include "thrust/device_vector.h"
2120

2221
namespace centerpoint
2322
{

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

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

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>
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"
2423

2524
#include <vector>
2625

0 commit comments

Comments
 (0)