Skip to content

Commit ad395bd

Browse files
KYabuuchiknzo25
andauthored
feat(autoware_cuda_pointcloud_preprocessor.): cherry-pickfor cuda pointcloud preprocessor (#2037)
* feat(autoware_pointcloud_preprocessor): templated version of the pointcloud concatenation (autowarefoundation#10298) * feat: refactored the concat into a templated design to allow cuda implementations and extend it to radars Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * fix: moved the concat cpp for consistency and component loading Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: removed unused dep Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * fix: missing virtual destructor Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * fix: fixed missing dep Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: removed unused var Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: refactored the cloud handler Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: updated documentation Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * fix: fixed rebase error Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: removed commented include Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: removed another rebase error induced print Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * fix: and yet another rebase induced error Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: changed method name Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: removing key from dict for peace of mind Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: reimplemented latest changes in the base branch Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: missed dep Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: spell Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: removed explicit template instantiation since clang tidy reported it was being done implicitly and thus redundant Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: added documentation regarding why allocation is done right after publishing Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: replaced at for extract+mapped Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: moved format_timestamp into its own file Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> --------- Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * feat(autoware_cuda_pointcloud_preprocessor): pointcloud concatenation (autowarefoundation#10300) * feat: cuda accelerated version of the pointcloud concatenation Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: removed duplicated include Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: changed to header blocks from pragmas :c Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: removed yaml and schema since this node uses the same interface as the non-gpu node Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: fixed rebased induced error Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * fix: used the wrong point type Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: changed pointer to auto Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: rewrote equation for clarity Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: added a comment regarding the reallocation strategy Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: reflected latest changes in the templated version of the concat Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: addressed cppcheck reports Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: fixed dead link Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: solving uncrustify conflicts Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: more uncrustify Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: yet another uncrustify related error Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: hopefully last uncrustify error Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> * chore: now fixing uncrustify on source files Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> --------- Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> --------- Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp> Co-authored-by: Kenzo Lobos Tsunekawa <kenzo.lobos@tier4.jp>
1 parent d1cbe8e commit ad395bd

35 files changed

+2178
-1038
lines changed

sensing/autoware_cuda_pointcloud_preprocessor/CMakeLists.txt

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,10 @@ include_directories(
3737
list(APPEND CUDA_NVCC_FLAGS "--expt-relaxed-constexpr -diag-suppress 20012") # cSpell: ignore expt
3838

3939
cuda_add_library(cuda_pointcloud_preprocessor_lib SHARED
40+
src/cuda_concatenate_data/cuda_combine_cloud_handler.cpp
41+
src/cuda_concatenate_data/cuda_combine_cloud_handler_kernel.cu
42+
src/cuda_concatenate_data/cuda_cloud_collector.cpp
43+
src/cuda_concatenate_data/cuda_collector_matching_strategy.cpp
4044
src/cuda_pointcloud_preprocessor/cuda_pointcloud_preprocessor.cu
4145
src/cuda_pointcloud_preprocessor/common_kernels.cu
4246
src/cuda_pointcloud_preprocessor/organize_kernels.cu
@@ -65,14 +69,22 @@ target_include_directories(cuda_pointcloud_preprocessor_lib SYSTEM PRIVATE
6569

6670
# Targets
6771
ament_auto_add_library(cuda_pointcloud_preprocessor SHARED
72+
src/cuda_concatenate_data/cuda_concatenate_and_time_sync_node.cpp
6873
src/cuda_pointcloud_preprocessor/cuda_pointcloud_preprocessor_node.cpp
6974
)
7075

7176
target_link_libraries(cuda_pointcloud_preprocessor
7277
${CUDA_LIBRARIES}
78+
${diagnostic_msgs_LIBRARIES}
7379
cuda_pointcloud_preprocessor_lib
7480
)
7581

82+
# ========== Concatenate and Sync data ==========
83+
rclcpp_components_register_node(cuda_pointcloud_preprocessor
84+
PLUGIN "autoware::cuda_pointcloud_preprocessor::CudaPointCloudConcatenateDataSynchronizerComponent"
85+
EXECUTABLE cuda_concatenate_and_time_sync_node)
86+
87+
# ========== Pointcloud preprocessor ==========
7688
rclcpp_components_register_node(cuda_pointcloud_preprocessor
7789
PLUGIN "autoware::cuda_pointcloud_preprocessor::CudaPointcloudPreprocessorNode"
7890
EXECUTABLE cuda_pointcloud_preprocessor_node

sensing/autoware_cuda_pointcloud_preprocessor/README.md

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -10,9 +10,10 @@ To alleviate this issue, this package reimplements most of the pipeline presente
1010

1111
A detailed description of each filter's algorithm is available in the following links.
1212

13-
| Filter Name | Description | Detail |
14-
| ---------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------- |
15-
| cuda_pointcloud_preprocessor | Implements the cropping, distortion correction, and outlier filtering (ring-based) of the `autoware_pointcloud_preprocessor`'s CPU versions. | [link](docs/cuda-pointcloud-preprocessor.md) |
13+
| Filter Name | Description | Detail |
14+
| ----------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------- | -------------------------------------------- |
15+
| cuda_pointcloud_preprocessor | Implements the cropping, distortion correction, and outlier filtering (ring-based) of the `autoware_pointcloud_preprocessor`'s CPU versions. | [link](docs/cuda-pointcloud-preprocessor.md) |
16+
| cuda_concatenate_and_time_sync_node | Implements pointcloud concatenation an synchronization following `autoware_pointcloud_preprocessor`'s CPU implementation. | [link](docs/cuda-concatenate-data.md) |
1617

1718
## (Optional) Future extensions / Unimplemented parts
1819

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
# cuda_concatenate_and_time_synchronize_node
2+
3+
This package is a cuda accelerated version of the one available in [autoware_cuda_pointcloud_preprocessor](../../autoware_pointcloud_preprocessor).
4+
As this node is templated, the overall design, algorithm, inputs, and outputs are the same.
5+
6+
The only change, corresponds to the pointcloud topics, which instead of using the standard `sensor_msgs::msg::PointCloud2` message type, they use the `cuda_blackboard` mechanism.
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,21 @@
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_CONCATENATE_DATA__CUDA_CLOUD_COLLECTOR_HPP_
16+
#define AUTOWARE__CUDA_POINTCLOUD_PREPROCESSOR__CUDA_CONCATENATE_DATA__CUDA_CLOUD_COLLECTOR_HPP_
17+
18+
#include "autoware/pointcloud_preprocessor/concatenate_data/cloud_collector.hpp"
19+
#include "cuda_combine_cloud_handler.hpp"
20+
21+
#endif // AUTOWARE__CUDA_POINTCLOUD_PREPROCESSOR__CUDA_CONCATENATE_DATA__CUDA_CLOUD_COLLECTOR_HPP_
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,60 @@
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+
#pragma once
16+
17+
#include "autoware/cuda_pointcloud_preprocessor/cuda_concatenate_data/cuda_traits.hpp"
18+
#include "autoware/pointcloud_preprocessor/concatenate_data/combine_cloud_handler.hpp"
19+
20+
#include <memory>
21+
#include <string>
22+
#include <unordered_map>
23+
#include <vector>
24+
25+
namespace autoware::pointcloud_preprocessor
26+
{
27+
28+
/* *INDENT-OFF* */
29+
template <>
30+
class CombineCloudHandler<CudaPointCloud2Traits> : public CombineCloudHandlerBase
31+
{
32+
protected:
33+
struct CudaConcatStruct
34+
{
35+
cudaStream_t stream;
36+
std::unique_ptr<CudaPointCloud2Traits::PointCloudMessage> cloud_ptr;
37+
std::size_t max_pointcloud_size{0};
38+
};
39+
40+
std::unordered_map<std::string, CudaConcatStruct> cuda_concat_struct_map_;
41+
std::unique_ptr<CudaPointCloud2Traits::PointCloudMessage> concatenated_cloud_ptr_;
42+
std::size_t max_concat_pointcloud_size_{0};
43+
std::mutex mutex_;
44+
45+
public:
46+
CombineCloudHandler(
47+
rclcpp::Node & node, const std::vector<std::string> & input_topics, std::string output_frame,
48+
bool is_motion_compensated, bool publish_synchronized_pointcloud,
49+
bool keep_input_frame_in_synchronized_pointcloud);
50+
51+
ConcatenatedCloudResult<CudaPointCloud2Traits> combine_pointclouds(
52+
std::unordered_map<
53+
std::string, typename CudaPointCloud2Traits::PointCloudMessage::ConstSharedPtr> &
54+
topic_to_cloud_map);
55+
56+
void allocate_pointclouds() override;
57+
};
58+
/* *INDENT-ON* */
59+
60+
} // namespace autoware::pointcloud_preprocessor
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,59 @@
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+
/* *INDENT-OFF* */
16+
#ifndef AUTOWARE__CUDA_POINTCLOUD_PREPROCESSOR__CUDA_CONCATENATE_DATA__CUDA_COMBINE_CLOUD_HANDLER_KERNEL_HPP_
17+
#define AUTOWARE__CUDA_POINTCLOUD_PREPROCESSOR__CUDA_CONCATENATE_DATA__CUDA_COMBINE_CLOUD_HANDLER_KERNEL_HPP_
18+
19+
#include <cuda_runtime.h>
20+
21+
#include <cstdint>
22+
23+
namespace autoware::pointcloud_preprocessor
24+
{
25+
26+
struct TransformStruct
27+
{
28+
float translation_x;
29+
float translation_y;
30+
float translation_z;
31+
float m11;
32+
float m12;
33+
float m13;
34+
float m21;
35+
float m22;
36+
float m23;
37+
float m31;
38+
float m32;
39+
float m33;
40+
};
41+
42+
struct PointTypeStruct
43+
{
44+
float x;
45+
float y;
46+
float z;
47+
std::uint8_t intensity;
48+
std::uint8_t return_type;
49+
std::uint16_t channel;
50+
};
51+
52+
void transform_launch(
53+
const PointTypeStruct * input_points, int num_points, TransformStruct transform,
54+
PointTypeStruct * output_points, cudaStream_t & stream);
55+
56+
} // namespace autoware::pointcloud_preprocessor
57+
58+
#endif // AUTOWARE__CUDA_POINTCLOUD_PREPROCESSOR__CUDA_CONCATENATE_DATA__CUDA_COMBINE_CLOUD_HANDLER_KERNEL_HPP_
59+
/* *INDENT-ON* */
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,47 @@
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+
/* *INDENT-OFF* */
16+
#ifndef AUTOWARE__CUDA_POINTCLOUD_PREPROCESSOR__CUDA_CONCATENATE_DATA__CUDA_CONCATENATE_AND_TIME_SYNC_NODE_HPP_
17+
#define AUTOWARE__CUDA_POINTCLOUD_PREPROCESSOR__CUDA_CONCATENATE_DATA__CUDA_CONCATENATE_AND_TIME_SYNC_NODE_HPP_
18+
19+
#include "autoware/cuda_pointcloud_preprocessor/cuda_concatenate_data/cuda_traits.hpp"
20+
#include "autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_node.hpp"
21+
22+
#include <cuda_blackboard/cuda_blackboard_publisher.hpp>
23+
#include <cuda_blackboard/cuda_blackboard_subscriber.hpp>
24+
#include <cuda_blackboard/cuda_pointcloud2.hpp>
25+
#include <rclcpp/rclcpp.hpp>
26+
27+
namespace autoware::cuda_pointcloud_preprocessor
28+
{
29+
30+
class CudaPointCloudConcatenateDataSynchronizerComponent
31+
: public autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponentTemplated<
32+
autoware::pointcloud_preprocessor::CudaPointCloud2Traits>
33+
{
34+
public:
35+
explicit CudaPointCloudConcatenateDataSynchronizerComponent(
36+
const rclcpp::NodeOptions & node_options)
37+
: autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponentTemplated<
38+
autoware::pointcloud_preprocessor::CudaPointCloud2Traits>(node_options)
39+
{
40+
}
41+
~CudaPointCloudConcatenateDataSynchronizerComponent() override = default;
42+
};
43+
44+
} // namespace autoware::cuda_pointcloud_preprocessor
45+
46+
#endif // AUTOWARE__CUDA_POINTCLOUD_PREPROCESSOR__CUDA_CONCATENATE_DATA__CUDA_CONCATENATE_AND_TIME_SYNC_NODE_HPP_
47+
/* *INDENT-ON* */
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,34 @@
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_CONCATENATE_DATA__CUDA_TRAITS_HPP_
16+
#define AUTOWARE__CUDA_POINTCLOUD_PREPROCESSOR__CUDA_CONCATENATE_DATA__CUDA_TRAITS_HPP_
17+
18+
#include <cuda_blackboard/cuda_blackboard_publisher.hpp>
19+
#include <cuda_blackboard/cuda_blackboard_subscriber.hpp>
20+
#include <cuda_blackboard/cuda_pointcloud2.hpp>
21+
22+
namespace autoware::pointcloud_preprocessor
23+
{
24+
25+
struct CudaPointCloud2Traits
26+
{
27+
using PointCloudMessage = cuda_blackboard::CudaPointCloud2;
28+
using PublisherType = cuda_blackboard::CudaBlackboardPublisher<PointCloudMessage>;
29+
using SubscriberType = cuda_blackboard::CudaBlackboardSubscriber<PointCloudMessage>;
30+
};
31+
32+
} // namespace autoware::pointcloud_preprocessor
33+
34+
#endif // AUTOWARE__CUDA_POINTCLOUD_PREPROCESSOR__CUDA_CONCATENATE_DATA__CUDA_TRAITS_HPP_
Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
<launch>
2+
<arg name="input/twist" default="/sensing/vehicle_velocity_converter/twist_with_covariance"/>
3+
<arg name="output" default="/sensing/lidar/concatenated/pointcloud"/>
4+
<!-- Parameter -->
5+
<arg name="param_file" default="$(find-pkg-share autoware_pointcloud_preprocessor)/config/concatenate_and_time_sync_node.param.yaml"/>
6+
<node pkg="autoware_cuda_pointcloud_preprocessor" exec="cuda_concatenate_and_time_sync_node" name="cuda_concatenate_and_time_sync_node" output="screen">
7+
<remap from="~/input/twist" to="$(var input/twist)"/>
8+
<remap from="output" to="$(var output)"/>
9+
<param from="$(var param_file)"/>
10+
</node>
11+
</launch>
Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,22 @@
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+
#include "autoware/cuda_pointcloud_preprocessor/cuda_concatenate_data/cuda_cloud_collector.hpp"
16+
17+
#include "autoware/cuda_pointcloud_preprocessor/cuda_concatenate_data/cuda_traits.hpp"
18+
19+
/* *INDENT-OFF* */
20+
template class autoware::pointcloud_preprocessor::CloudCollector<
21+
autoware::pointcloud_preprocessor::CudaPointCloud2Traits>;
22+
/* *INDENT-ON* */
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,23 @@
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+
#include "autoware/cuda_pointcloud_preprocessor/cuda_concatenate_data/cuda_traits.hpp"
16+
#include "autoware/pointcloud_preprocessor/concatenate_data/collector_matching_strategy.hpp"
17+
18+
/* *INDENT-OFF* */
19+
template class autoware::pointcloud_preprocessor::NaiveMatchingStrategy<
20+
autoware::pointcloud_preprocessor::CudaPointCloud2Traits>;
21+
template class autoware::pointcloud_preprocessor::AdvancedMatchingStrategy<
22+
autoware::pointcloud_preprocessor::CudaPointCloud2Traits>;
23+
/* *INDENT-ON* */

0 commit comments

Comments
 (0)