From 9cd3b2fa1f8966357a4d307953dd0faa21c2ae0f Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Wed, 26 Jun 2024 00:22:16 +0000 Subject: [PATCH] style(pre-commit): autofix --- .../src/vector_map_filter/lanelet2_map_filter_nodelet.cpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/sensing/pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_nodelet.cpp b/sensing/pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_nodelet.cpp index 8f7cb2abec6a4..c98e95c276d00 100644 --- a/sensing/pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_nodelet.cpp @@ -226,9 +226,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);