From 2759e85ea0a2a707968bf700665bb71e5971c41b Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 7 Aug 2023 09:43:42 +0000 Subject: [PATCH] style(pre-commit): autofix --- .../src/pointpainting_fusion/node.cpp | 11 +++++++---- .../src/pointpainting_fusion/preprocess_kernel.cu | 4 ++-- 2 files changed, 9 insertions(+), 6 deletions(-) diff --git a/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp b/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp index 06466d47eee8d..5253ac192c786 100644 --- a/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp @@ -22,9 +22,9 @@ #include #include #include +#include #include #include -#include #include @@ -115,9 +115,12 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt const std::string head_engine_path = this->declare_parameter("head_engine_path", ""); class_names_ = this->declare_parameter>("class_names"); - const auto paint_class_names = this->declare_parameter>("paint_class_names"); + const auto paint_class_names = + this->declare_parameter>("paint_class_names"); std::vector classes_{"CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"}; - if (std::find(paint_class_names.begin(), paint_class_names.end(), "TRUCK") != paint_class_names.end()) { + if ( + std::find(paint_class_names.begin(), paint_class_names.end(), "TRUCK") != + paint_class_names.end()) { isClassTable_["CAR"] = std::bind(&isCar, std::placeholders::_1); } else { isClassTable_["CAR"] = std::bind(&isVehicle, std::placeholders::_1); @@ -321,7 +324,7 @@ dc | dc dc dc dc ||zc| float p_y = *reinterpret_cast(&data[stride + y_offset]); float p_z = *reinterpret_cast(&data[stride + z_offset]); point_lidar << p_x, p_y, p_z; - point_camera = lidar2cam_affine * point_lidar; + point_camera = lidar2cam_affine * point_lidar; p_x = point_camera.x(); p_y = point_camera.y(); p_z = point_camera.z(); diff --git a/perception/image_projection_based_fusion/src/pointpainting_fusion/preprocess_kernel.cu b/perception/image_projection_based_fusion/src/pointpainting_fusion/preprocess_kernel.cu index 632dbd2b53435..7aab97b238e02 100644 --- a/perception/image_projection_based_fusion/src/pointpainting_fusion/preprocess_kernel.cu +++ b/perception/image_projection_based_fusion/src/pointpainting_fusion/preprocess_kernel.cu @@ -39,8 +39,8 @@ const std::size_t MAX_POINT_IN_VOXEL_SIZE = 32; // the same as max_point_in_vox const std::size_t WARPS_PER_BLOCK = 4; const std::size_t ENCODER_IN_FEATURE_SIZE = 12; // same as encoder_in_feature_size_ in config.hpp const int POINT_FEATURE_SIZE = 7; -// const std::size_t ENCODER_IN_FEATURE_SIZE = 14; // same as encoder_in_feature_size_ in config.hpp -// const int POINT_FEATURE_SIZE = 9; +// const std::size_t ENCODER_IN_FEATURE_SIZE = 14; // same as encoder_in_feature_size_ in +// config.hpp const int POINT_FEATURE_SIZE = 9; // cspell: ignore divup std::size_t divup(const std::size_t a, const std::size_t b)