Skip to content

Commit 3b56716

Browse files
authored
fix: enable to copy all information in pickup based pointcloud downsampler (#9686)
enable to copy all information in downsampler Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com>
1 parent 4c1153f commit 3b56716

File tree

1 file changed

+1
-9
lines changed

1 file changed

+1
-9
lines changed

sensing/autoware_pointcloud_preprocessor/src/downsample_filter/pickup_based_voxel_grid_downsample_filter_node.cpp

+1-9
Original file line numberDiff line numberDiff line change
@@ -124,15 +124,7 @@ void PickupBasedVoxelGridDownsampleFilterComponent::filter(
124124
size_t output_global_offset = 0;
125125
output.data.resize(voxel_map.size() * input->point_step);
126126
for (const auto & kv : voxel_map) {
127-
std::memcpy(
128-
&output.data[output_global_offset + x_offset], &input->data[kv.second + x_offset],
129-
sizeof(float));
130-
std::memcpy(
131-
&output.data[output_global_offset + y_offset], &input->data[kv.second + y_offset],
132-
sizeof(float));
133-
std::memcpy(
134-
&output.data[output_global_offset + z_offset], &input->data[kv.second + z_offset],
135-
sizeof(float));
127+
std::memcpy(&output.data[output_global_offset], &input->data[kv.second], input->point_step);
136128
output_global_offset += input->point_step;
137129
}
138130

0 commit comments

Comments
 (0)