From 5dcb52b55ea9ef39f330a1a550a91d5db9e1afac Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Mon, 18 Nov 2024 10:23:49 +0900 Subject: [PATCH] feat(autoware_traffic_light_multi_camera_fusion): resolve clang-tidy error (#9336) * feat(autoware_traffic_light_multi_camera_fusion): resolve clang-tidy error Signed-off-by: Y.Hisaki * add const to argument Signed-off-by: Y.Hisaki --------- Signed-off-by: Y.Hisaki --- .../package.xml | 1 + ...traffic_light_multi_camera_fusion_node.cpp | 6 ++-- ...traffic_light_multi_camera_fusion_node.hpp | 30 +++++++++---------- 3 files changed, 19 insertions(+), 18 deletions(-) diff --git a/perception/autoware_traffic_light_multi_camera_fusion/package.xml b/perception/autoware_traffic_light_multi_camera_fusion/package.xml index e029c79def9f9..111e34030c870 100644 --- a/perception/autoware_traffic_light_multi_camera_fusion/package.xml +++ b/perception/autoware_traffic_light_multi_camera_fusion/package.xml @@ -16,6 +16,7 @@ autoware_lanelet2_extension autoware_map_msgs autoware_perception_msgs + message_filters rclcpp rclcpp_components sensor_msgs diff --git a/perception/autoware_traffic_light_multi_camera_fusion/src/traffic_light_multi_camera_fusion_node.cpp b/perception/autoware_traffic_light_multi_camera_fusion/src/traffic_light_multi_camera_fusion_node.cpp index 70841b936af37..08c6600d91923 100644 --- a/perception/autoware_traffic_light_multi_camera_fusion/src/traffic_light_multi_camera_fusion_node.cpp +++ b/perception/autoware_traffic_light_multi_camera_fusion/src/traffic_light_multi_camera_fusion_node.cpp @@ -102,8 +102,8 @@ V at_or(const std::unordered_map & map, const K & key, const V & value) autoware_perception_msgs::msg::TrafficLightElement convert( const tier4_perception_msgs::msg::TrafficLightElement & input) { - typedef tier4_perception_msgs::msg::TrafficLightElement OldElem; - typedef autoware_perception_msgs::msg::TrafficLightElement NewElem; + using OldElem = tier4_perception_msgs::msg::TrafficLightElement; + using NewElem = autoware_perception_msgs::msg::TrafficLightElement; static const std::unordered_map color_map( {{OldElem::RED, NewElem::RED}, {OldElem::AMBER, NewElem::AMBER}, @@ -292,7 +292,7 @@ void MultiCameraFusion::multiCameraFusion(std::map & fused } void MultiCameraFusion::groupFusion( - std::map & fused_record_map, + const std::map & fused_record_map, std::map & grouped_record_map) { grouped_record_map.clear(); diff --git a/perception/autoware_traffic_light_multi_camera_fusion/src/traffic_light_multi_camera_fusion_node.hpp b/perception/autoware_traffic_light_multi_camera_fusion/src/traffic_light_multi_camera_fusion_node.hpp index 23bc59c26b293..bf41df9bb3a24 100644 --- a/perception/autoware_traffic_light_multi_camera_fusion/src/traffic_light_multi_camera_fusion_node.hpp +++ b/perception/autoware_traffic_light_multi_camera_fusion/src/traffic_light_multi_camera_fusion_node.hpp @@ -65,16 +65,16 @@ bool operator<(const FusionRecordArr & r1, const FusionRecordArr & r2) class MultiCameraFusion : public rclcpp::Node { public: - typedef sensor_msgs::msg::CameraInfo CamInfoType; - typedef tier4_perception_msgs::msg::TrafficLightRoi RoiType; - typedef tier4_perception_msgs::msg::TrafficLight SignalType; - typedef tier4_perception_msgs::msg::TrafficLightArray SignalArrayType; - typedef tier4_perception_msgs::msg::TrafficLightRoiArray RoiArrayType; - typedef tier4_perception_msgs::msg::TrafficLightRoi::_traffic_light_id_type IdType; - typedef autoware_perception_msgs::msg::TrafficLightGroup NewSignalType; - typedef autoware_perception_msgs::msg::TrafficLightGroupArray NewSignalArrayType; + using CamInfoType = sensor_msgs::msg::CameraInfo; + using RoiType = tier4_perception_msgs::msg::TrafficLightRoi; + using SignalType = tier4_perception_msgs::msg::TrafficLight; + using SignalArrayType = tier4_perception_msgs::msg::TrafficLightArray; + using RoiArrayType = tier4_perception_msgs::msg::TrafficLightRoiArray; + using IdType = tier4_perception_msgs::msg::TrafficLightRoi::_traffic_light_id_type; + using NewSignalType = autoware_perception_msgs::msg::TrafficLightGroup; + using NewSignalArrayType = autoware_perception_msgs::msg::TrafficLightGroupArray; - typedef std::pair RecordArrayType; + using RecordArrayType = std::pair; explicit MultiCameraFusion(const rclcpp::NodeOptions & node_options); @@ -91,14 +91,14 @@ class MultiCameraFusion : public rclcpp::Node const std::map & grouped_record_map, NewSignalArrayType & msg_out); void groupFusion( - std::map & fused_record_map, + const std::map & fused_record_map, std::map & grouped_record_map); - typedef mf::sync_policies::ExactTime ExactSyncPolicy; - typedef mf::Synchronizer ExactSync; - typedef mf::sync_policies::ApproximateTime - ApproximateSyncPolicy; - typedef mf::Synchronizer ApproximateSync; + using ExactSyncPolicy = mf::sync_policies::ExactTime; + using ExactSync = mf::Synchronizer; + using ApproximateSyncPolicy = + mf::sync_policies::ApproximateTime; + using ApproximateSync = mf::Synchronizer; std::vector>> signal_subs_; std::vector>> roi_subs_;