From a5e9d286220d3985c78ea93fcf188ff3096049c4 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Wed, 27 Nov 2024 19:07:31 +0900 Subject: [PATCH] fix(autoware_image_projection_based_fusion): fix clang-diagnostic-unused-private-field (#9473) * fix: clang-diagnostic-unused-private-field Signed-off-by: kobayu858 * fix: build error Signed-off-by: kobayu858 --------- Signed-off-by: kobayu858 --- .../autoware_image_projection_based_fusion/CMakeLists.txt | 1 + .../include/autoware/image_projection_based_fusion/debugger.hpp | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/perception/autoware_image_projection_based_fusion/CMakeLists.txt b/perception/autoware_image_projection_based_fusion/CMakeLists.txt index 73d305d2ab2a8..921a46ccebe3e 100644 --- a/perception/autoware_image_projection_based_fusion/CMakeLists.txt +++ b/perception/autoware_image_projection_based_fusion/CMakeLists.txt @@ -2,6 +2,7 @@ cmake_minimum_required(VERSION 3.14) project(autoware_image_projection_based_fusion) # add_compile_options(-Wno-unknown-pragmas) add_compile_options(-Wno-unknown-pragmas -fopenmp) +add_compile_options(-Wno-error=attributes) find_package(autoware_cmake REQUIRED) find_package(OpenCV REQUIRED) diff --git a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/debugger.hpp b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/debugger.hpp index ba7f8b6ca3496..d74347772ef10 100644 --- a/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/debugger.hpp +++ b/perception/autoware_image_projection_based_fusion/include/autoware/image_projection_based_fusion/debugger.hpp @@ -56,7 +56,7 @@ class Debugger void imageCallback( const sensor_msgs::msg::Image::ConstSharedPtr input_image_msg, const std::size_t image_id); - rclcpp::Node * node_ptr_; + [[maybe_unused]] rclcpp::Node * node_ptr_; std::shared_ptr image_transport_; std::vector input_camera_topics_; std::vector image_subs_;