From 798be97a8e85729f397ab5c034fc8742a7ed9dbf Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 9 Apr 2024 13:21:04 +0000 Subject: [PATCH] style(pre-commit): autofix --- planning/behavior_velocity_planner/src/node.cpp | 7 ++++--- planning/behavior_velocity_planner/src/node.hpp | 4 ++-- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/planning/behavior_velocity_planner/src/node.cpp b/planning/behavior_velocity_planner/src/node.cpp index 5aaecfacd28d6..659c233ab958e 100644 --- a/planning/behavior_velocity_planner/src/node.cpp +++ b/planning/behavior_velocity_planner/src/node.cpp @@ -436,11 +436,12 @@ autoware_auto_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generatePath std::make_shared(planner_data), *input_path_msg); // screening - const auto filtered_path = ::behavior_velocity_planner::filterLitterPathPoint(to_path(velocity_planned_path)); + const auto filtered_path = + ::behavior_velocity_planner::filterLitterPathPoint(to_path(velocity_planned_path)); // interpolation - const auto interpolated_path_msg = - ::behavior_velocity_planner::interpolatePath(filtered_path, forward_path_length_, behavior_output_path_interval_); + const auto interpolated_path_msg = ::behavior_velocity_planner::interpolatePath( + filtered_path, forward_path_length_, behavior_output_path_interval_); // check stop point output_path_msg = ::behavior_velocity_planner::filterStopPathPoint(interpolated_path_msg); diff --git a/planning/behavior_velocity_planner/src/node.hpp b/planning/behavior_velocity_planner/src/node.hpp index 3814562f11cca..a7815a9dac35a 100644 --- a/planning/behavior_velocity_planner/src/node.hpp +++ b/planning/behavior_velocity_planner/src/node.hpp @@ -49,11 +49,11 @@ namespace autoware namespace behavior_velocity_planner { using autoware_auto_mapping_msgs::msg::HADMapBin; -using tier4_planning_msgs::msg::VelocityLimit; -using ::behavior_velocity_planner::PlannerData; 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 {