From eec508e5d382fa81f5ce051e1ef6aa2648bada8d Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Sat, 14 Sep 2024 00:23:11 +0000 Subject: [PATCH] style(pre-commit): autofix --- .../src/vector_map_filter/lanelet2_map_filter_node.cpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_node.cpp index ee788a2fc807a..81d9348aed739 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_node.cpp @@ -228,9 +228,8 @@ void Lanelet2MapFilterComponent::pointcloudCallback(const PointCloud2ConstPtr cl if (!transformPointCloud("map", cloud_msg, input_transformed_cloud_ptr.get())) { RCLCPP_ERROR_STREAM_THROTTLE( this->get_logger(), *this->get_clock(), std::chrono::milliseconds(10000).count(), - "Failed transform from " - << "map" - << " to " << cloud_msg->header.frame_id); + "Failed transform from " << "map" + << " to " << cloud_msg->header.frame_id); return; } pcl::PointCloud::Ptr cloud(new pcl::PointCloud);