Skip to content
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.

Commit 42509c2

Browse files
committedMay 12, 2024·
feat: moved preprocessing to cuda
Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp>
1 parent 569d56c commit 42509c2

File tree

5 files changed

+52
-20
lines changed

5 files changed

+52
-20
lines changed
 

‎perception/lidar_apollo_instance_segmentation/src/detector.cpp

+23-1
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,8 @@
1616

1717
#include "lidar_apollo_instance_segmentation/feature_map.hpp"
1818

19+
#include <sensor_msgs/point_cloud2_iterator.hpp>
20+
1921
#include <NvCaffeParser.h>
2022
#include <NvInfer.h>
2123
#include <pcl_conversions/pcl_conversions.h>
@@ -125,7 +127,27 @@ bool LidarApolloInstanceSegmentation::detectDynamicObjects(
125127

126128
// convert from ros to pcl
127129
pcl::PointCloud<pcl::PointXYZI>::Ptr pcl_pointcloud_raw_ptr(new pcl::PointCloud<pcl::PointXYZI>);
128-
pcl::fromROSMsg(transformed_cloud, *pcl_pointcloud_raw_ptr);
130+
// pcl::fromROSMsg(transformed_cloud, *pcl_pointcloud_raw_ptr);
131+
132+
auto pcl_pointcloud_raw = *pcl_pointcloud_raw_ptr;
133+
pcl_pointcloud_raw.width = transformed_cloud.width;
134+
pcl_pointcloud_raw.height = transformed_cloud.height;
135+
pcl_pointcloud_raw.is_dense = transformed_cloud.is_dense == 1;
136+
pcl_pointcloud_raw.resize(transformed_cloud.width * transformed_cloud.height);
137+
138+
sensor_msgs::PointCloud2ConstIterator<float> it_x(transformed_cloud, "x");
139+
sensor_msgs::PointCloud2ConstIterator<float> it_y(transformed_cloud, "y");
140+
sensor_msgs::PointCloud2ConstIterator<float> it_z(transformed_cloud, "z");
141+
sensor_msgs::PointCloud2ConstIterator<uint8_t> it_intensity(transformed_cloud, "intensity");
142+
143+
for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z, ++it_intensity) {
144+
pcl::PointXYZI point;
145+
point.x = *it_x;
146+
point.y = *it_y;
147+
point.z = *it_z;
148+
point.intensity = static_cast<float>(*it_intensity);
149+
pcl_pointcloud_raw.emplace_back(std::move(point));
150+
}
129151

130152
// generate feature map
131153
std::shared_ptr<FeatureMapInterface> feature_map_ptr =

‎perception/raindrop_cluster_filter/src/low_intensity_cluster_filter.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -123,9 +123,9 @@ bool LowIntensityClusterFilter::isValidatedCluster(const sensor_msgs::msg::Point
123123
RCLCPP_WARN(get_logger(), "Invalid point cloud data. point_step is less than 16.");
124124
return true;
125125
}
126-
for (sensor_msgs::PointCloud2ConstIterator<float> iter(cluster, "intensity"); iter != iter.end();
127-
++iter) {
128-
mean_intensity += *iter;
126+
for (sensor_msgs::PointCloud2ConstIterator<uint8_t> iter(cluster, "intensity");
127+
iter != iter.end(); ++iter) {
128+
mean_intensity += static_cast<float>(*iter);
129129
}
130130
const size_t num_points = cluster.width * cluster.height;
131131
mean_intensity /= static_cast<double>(num_points);

‎sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp

+5-2
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,10 @@ using point_cloud_msg_wrapper::PointCloud2Modifier;
3333
class RingOutlierFilterComponent : public pointcloud_preprocessor::Filter
3434
{
3535
protected:
36+
using InputPointIndex = autoware_point_types::PointXYZIRCAEDTIndex;
37+
using InputPointType = autoware_point_types::PointXYZIRCAEDT;
38+
using OutputPointType = autoware_point_types::PointXYZIRC;
39+
3640
virtual void filter(
3741
const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output);
3842

@@ -75,8 +79,7 @@ class RingOutlierFilterComponent : public pointcloud_preprocessor::Filter
7579
}
7680

7781
void setUpPointCloudFormat(
78-
const PointCloud2ConstPtr & input, PointCloud2 & formatted_points, size_t points_size,
79-
size_t num_fields);
82+
const PointCloud2ConstPtr & input, PointCloud2 & formatted_points, size_t points_size);
8083

8184
public:
8285
PCL_MAKE_ALIGNED_OPERATOR_NEW

‎sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp

+8-5
Original file line numberDiff line numberDiff line change
@@ -251,29 +251,32 @@ bool DistortionCorrectorComponent::undistortPointCloud(
251251
// If there is a point that cannot be associated, record it to issue a warning
252252
bool twist_time_stamp_is_too_late = false;
253253
bool imu_time_stamp_is_too_late = false;
254+
double global_point_stamp;
254255

255256
for (; it_x != it_x.end(); ++it_x, ++it_y, ++it_z, ++it_time_stamp) {
256-
while (twist_it != std::end(twist_queue_) - 1 && *it_time_stamp > twist_stamp) {
257+
global_point_stamp =
258+
points.header.stamp.sec + 1e-9 * (points.header.stamp.nanosec + *it_time_stamp);
259+
while (twist_it != std::end(twist_queue_) - 1 && global_point_stamp > twist_stamp) {
257260
++twist_it;
258261
twist_stamp = rclcpp::Time(twist_it->header.stamp).seconds();
259262
}
260263

261264
float v{static_cast<float>(twist_it->twist.linear.x)};
262265
float w{static_cast<float>(twist_it->twist.angular.z)};
263266

264-
if (std::abs(*it_time_stamp - twist_stamp) > 0.1) {
267+
if (std::abs(global_point_stamp - twist_stamp) > 0.1) {
265268
twist_time_stamp_is_too_late = true;
266269
v = 0.0f;
267270
w = 0.0f;
268271
}
269272

270273
if (use_imu_ && !angular_velocity_queue_.empty()) {
271-
while (imu_it != std::end(angular_velocity_queue_) - 1 && *it_time_stamp > imu_stamp) {
274+
while (imu_it != std::end(angular_velocity_queue_) - 1 && global_point_stamp > imu_stamp) {
272275
++imu_it;
273276
imu_stamp = rclcpp::Time(imu_it->header.stamp).seconds();
274277
}
275278

276-
if (std::abs(*it_time_stamp - imu_stamp) > 0.1) {
279+
if (std::abs(global_point_stamp - imu_stamp) > 0.1) {
277280
imu_time_stamp_is_too_late = true;
278281
} else {
279282
w = static_cast<float>(imu_it->vector.z);
@@ -309,7 +312,7 @@ bool DistortionCorrectorComponent::undistortPointCloud(
309312
*it_y = static_cast<float>(undistorted_point.getY());
310313
*it_z = static_cast<float>(undistorted_point.getZ());
311314

312-
prev_time_stamp_sec = *it_time_stamp;
315+
prev_time_stamp_sec = global_point_stamp;
313316
}
314317

315318
if (twist_time_stamp_is_too_late) {

‎sensing/pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_nodelet.cpp

+13-9
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818

1919
#include <sensor_msgs/point_cloud2_iterator.hpp>
2020

21+
#include <pcl/for_each_type.h>
2122
#include <pcl/search/pcl_search.h>
2223

2324
#include <algorithm>
@@ -232,10 +233,10 @@ void RingOutlierFilterComponent::faster_filter(
232233
}
233234
}
234235

235-
setUpPointCloudFormat(input, output, output_size, /*num_fields=*/4);
236+
setUpPointCloudFormat(input, output, output_size);
236237

237238
if (publish_outlier_pointcloud_) {
238-
setUpPointCloudFormat(input, outlier_points, outlier_points_size, /*num_fields=*/4);
239+
setUpPointCloudFormat(input, outlier_points, outlier_points_size);
239240
outlier_pointcloud_publisher_->publish(outlier_points);
240241
}
241242

@@ -297,8 +298,7 @@ rcl_interfaces::msg::SetParametersResult RingOutlierFilterComponent::paramCallba
297298
}
298299

299300
void RingOutlierFilterComponent::setUpPointCloudFormat(
300-
const PointCloud2ConstPtr & input, PointCloud2 & formatted_points, size_t points_size,
301-
size_t num_fields)
301+
const PointCloud2ConstPtr & input, PointCloud2 & formatted_points, size_t points_size)
302302
{
303303
formatted_points.data.resize(points_size);
304304
// Note that `input->header.frame_id` is data before converted when `transform_info.need_transform
@@ -312,11 +312,15 @@ void RingOutlierFilterComponent::setUpPointCloudFormat(
312312
formatted_points.is_bigendian = input->is_bigendian;
313313
formatted_points.is_dense = input->is_dense;
314314

315-
sensor_msgs::PointCloud2Modifier pcd_modifier(formatted_points);
316-
pcd_modifier.setPointCloud2Fields(
317-
num_fields, "x", 1, sensor_msgs::msg::PointField::FLOAT32, "y", 1,
318-
sensor_msgs::msg::PointField::FLOAT32, "z", 1, sensor_msgs::msg::PointField::FLOAT32,
319-
"intensity", 1, sensor_msgs::msg::PointField::FLOAT32);
315+
// pcl::PCLPointCloud2 pcl_aux;
316+
sensor_msgs::msg::PointCloud2 msg_aux;
317+
// pcl_conversions::moveFromPCL(pcl_pc2, cloud);
318+
pcl::toROSMsg(pcl::PointCloud<OutputPointType>(), msg_aux);
319+
formatted_points.fields = msg_aux.fields;
320+
// pcl::for_each_type<typename pcl::traits::fieldList<OutputPointType>::type>
321+
// pcl::detail::FieldAdder<OutputPointType>(formatted_points.fields); pcl::for_each_type<typename
322+
// pcl::traits::fieldList<OutputPointType>::type>
323+
// (pcl::detail::FieldAdder<OutputPointType>(formatted_points.fields));
320324
}
321325

322326
} // namespace pointcloud_preprocessor

0 commit comments

Comments
 (0)
Please sign in to comment.