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(