From 5e1188fd02788a41bfe813acb78daf65bc53fa62 Mon Sep 17 00:00:00 2001 From: Shintaro Tomie <58775300+Shin-kyoto@users.noreply.github.com> Date: Tue, 20 Aug 2024 08:15:15 +0900 Subject: [PATCH] feat(pointcloud_preprocessor)!: revert "fix: added temporary retrocompatibility to old perception data (#7929)" (#8397) * feat!(pointcloud_preprocessor): Revert "fix: added temporary retrocompatibility to old perception data (#7929)" This reverts commit 6b9f164b123e2f6a6fedf7330e507d4b68e45a09. Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> * feat(pointcloud_preprocessor): minor grammar fix Co-authored-by: David Wong <33114676+drwnz@users.noreply.github.com> --------- Signed-off-by: Shin-kyoto <58775300+Shin-kyoto@users.noreply.github.com> Co-authored-by: Kenzo Lobos Tsunekawa Co-authored-by: David Wong <33114676+drwnz@users.noreply.github.com> --- .../autoware_pointcloud_preprocessor/src/filter.cpp | 11 ++--------- 1 file changed, 2 insertions(+), 9 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/filter.cpp b/sensing/autoware_pointcloud_preprocessor/src/filter.cpp index 854e93ed52ebc..de6549463e7ff 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/filter.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/filter.cpp @@ -359,19 +359,12 @@ bool autoware::pointcloud_preprocessor::Filter::convert_output_costly( void autoware::pointcloud_preprocessor::Filter::faster_input_indices_callback( const PointCloud2ConstPtr cloud, const PointIndicesConstPtr indices) { - // TODO(knzo25): This first branch is to give temporary compatibility with old perception data. - // Should be deleted soon - if (utils::is_data_layout_compatible_with_point_xyzi(*cloud)) { - RCLCPP_ERROR_THROTTLE( - get_logger(), *get_clock(), 10000, - "The pointcloud layout is compatible with PointXYZI. You may be using legacy " - "code/data. Continue at your own risk"); - } else if ( + if ( !utils::is_data_layout_compatible_with_point_xyzircaedt(*cloud) && !utils::is_data_layout_compatible_with_point_xyzirc(*cloud)) { RCLCPP_ERROR( get_logger(), - "The pointcloud layout is not compatible with PointXYZIRCAEDT/PointXYZIRC. Aborting"); + "The pointcloud layout is not compatible with PointXYZIRCAEDT or PointXYZIRC. Aborting"); if (utils::is_data_layout_compatible_with_point_xyziradrt(*cloud)) { RCLCPP_ERROR(