From e3c48cca7bcc7ac74b65f6d268568a476589705e Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Fri, 12 Apr 2024 17:03:27 +0200 Subject: [PATCH] fix(autoware_behavior_velocity_planner): fix some clang-tidy errors Signed-off-by: Esteve Fernandez --- planning/behavior_velocity_planner/src/node.cpp | 2 ++ planning/behavior_velocity_planner/src/node.hpp | 1 - planning/behavior_velocity_planner/src/planner_manager.hpp | 2 +- 3 files changed, 3 insertions(+), 2 deletions(-) diff --git a/planning/behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/src/node.cpp index 9da26637103b1..ed63067b4e6d1 100644 --- a/planning/behavior_velocity_planner/src/node.cpp +++ b/planning/behavior_velocity_planner/src/node.cpp @@ -54,6 +54,8 @@ rclcpp::SubscriptionOptions createSubscriptionOptions(rclcpp::Node * node_ptr) namespace autoware::behavior_velocity_planner { +using ::behavior_velocity_planner::TrafficSignalStamped; + namespace { diff --git a/planning/behavior_velocity_planner/src/node.hpp b/planning/behavior_velocity_planner/src/node.hpp index c4d903001cb4f..2392aef24bdca 100644 --- a/planning/behavior_velocity_planner/src/node.hpp +++ b/planning/behavior_velocity_planner/src/node.hpp @@ -50,7 +50,6 @@ using autoware_auto_mapping_msgs::msg::HADMapBin; using autoware_behavior_velocity_planner::srv::LoadPlugin; using autoware_behavior_velocity_planner::srv::UnloadPlugin; using ::behavior_velocity_planner::PlannerData; -using ::behavior_velocity_planner::TrafficSignalStamped; using tier4_planning_msgs::msg::VelocityLimit; class BehaviorVelocityPlannerNode : public rclcpp::Node diff --git a/planning/behavior_velocity_planner/src/planner_manager.hpp b/planning/behavior_velocity_planner/src/planner_manager.hpp index f9c1d0253de62..448210116e56b 100644 --- a/planning/behavior_velocity_planner/src/planner_manager.hpp +++ b/planning/behavior_velocity_planner/src/planner_manager.hpp @@ -52,7 +52,7 @@ class BehaviorVelocityPlannerManager const std::shared_ptr & planner_data, const autoware_auto_planning_msgs::msg::PathWithLaneId & input_path_msg); - diagnostic_msgs::msg::DiagnosticStatus getStopReasonDiag() const; + [[nodiscard]] diagnostic_msgs::msg::DiagnosticStatus getStopReasonDiag() const; private: diagnostic_msgs::msg::DiagnosticStatus stop_reason_diag_;