From 980cd07bf8e9061f6334aea66f1487ed73075662 Mon Sep 17 00:00:00 2001 From: Esteve Fernandez Date: Fri, 12 Apr 2024 16:23:51 +0200 Subject: [PATCH] fix(autoware_static_centerline_optimizer): fix clang-tidy issues Signed-off-by: Esteve Fernandez --- .../static_centerline_optimizer_node.hpp | 1 + .../autoware_static_centerline_optimizer/type_alias.hpp | 2 -- .../include/autoware_static_centerline_optimizer/utils.hpp | 4 +++- .../src/static_centerline_optimizer_node.cpp | 2 ++ 4 files changed, 6 insertions(+), 3 deletions(-) diff --git a/planning/static_centerline_optimizer/include/autoware_static_centerline_optimizer/static_centerline_optimizer_node.hpp b/planning/static_centerline_optimizer/include/autoware_static_centerline_optimizer/static_centerline_optimizer_node.hpp index 1955c8f922cd9..a89d94e3170fa 100644 --- a/planning/static_centerline_optimizer/include/autoware_static_centerline_optimizer/static_centerline_optimizer_node.hpp +++ b/planning/static_centerline_optimizer/include/autoware_static_centerline_optimizer/static_centerline_optimizer_node.hpp @@ -37,6 +37,7 @@ namespace autoware::static_centerline_optimizer using autoware_static_centerline_optimizer::srv::LoadMap; using autoware_static_centerline_optimizer::srv::PlanPath; using autoware_static_centerline_optimizer::srv::PlanRoute; +using ::route_handler::RouteHandler; class StaticCenterlineOptimizerNode : public rclcpp::Node { diff --git a/planning/static_centerline_optimizer/include/autoware_static_centerline_optimizer/type_alias.hpp b/planning/static_centerline_optimizer/include/autoware_static_centerline_optimizer/type_alias.hpp index 8189ee05b24b5..f11dafd63471f 100644 --- a/planning/static_centerline_optimizer/include/autoware_static_centerline_optimizer/type_alias.hpp +++ b/planning/static_centerline_optimizer/include/autoware_static_centerline_optimizer/type_alias.hpp @@ -36,10 +36,8 @@ using autoware_auto_planning_msgs::msg::PathWithLaneId; using autoware_auto_planning_msgs::msg::Trajectory; using autoware_auto_planning_msgs::msg::TrajectoryPoint; using autoware_planning_msgs::msg::LaneletRoute; -using route_handler::RouteHandler; using tier4_autoware_utils::LinearRing2d; using tier4_autoware_utils::LineString2d; -using tier4_autoware_utils::Point2d; using visualization_msgs::msg::MarkerArray; } // namespace autoware::static_centerline_optimizer diff --git a/planning/static_centerline_optimizer/include/autoware_static_centerline_optimizer/utils.hpp b/planning/static_centerline_optimizer/include/autoware_static_centerline_optimizer/utils.hpp index 51736565e2fff..0bb8a4597ef36 100644 --- a/planning/static_centerline_optimizer/include/autoware_static_centerline_optimizer/utils.hpp +++ b/planning/static_centerline_optimizer/include/autoware_static_centerline_optimizer/utils.hpp @@ -26,12 +26,14 @@ namespace autoware::static_centerline_optimizer::utils { +using ::route_handler::RouteHandler; + geometry_msgs::msg::Pose get_center_pose( const RouteHandler & route_handler, const size_t lanelet_id); PathWithLaneId get_path_with_lane_id( const RouteHandler & route_handler, const lanelet::ConstLanelets & lanelets, - const geometry_msgs::msg::Pose & start_pose, const double nearest_ego_dist_threshold, + const geometry_msgs::msg::Pose & start_pose, const double ego_nearest_dist_threshold, const double nearest_ego_yaw_threshold); void update_centerline( diff --git a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp index 08c62c9f40c2e..3e874af76a3fd 100644 --- a/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp +++ b/planning/static_centerline_optimizer/src/static_centerline_optimizer_node.cpp @@ -57,6 +57,8 @@ namespace autoware::static_centerline_optimizer { +using ::tier4_autoware_utils::Point2d; + namespace { Path convert_to_path(const PathWithLaneId & path_with_lane_id)