Skip to content

Commit 798be97

Browse files
style(pre-commit): autofix
1 parent e274b34 commit 798be97

File tree

2 files changed

+6
-5
lines changed

2 files changed

+6
-5
lines changed

planning/behavior_velocity_planner/src/node.cpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -436,11 +436,12 @@ autoware_auto_planning_msgs::msg::Path BehaviorVelocityPlannerNode::generatePath
436436
std::make_shared<const PlannerData>(planner_data), *input_path_msg);
437437

438438
// screening
439-
const auto filtered_path = ::behavior_velocity_planner::filterLitterPathPoint(to_path(velocity_planned_path));
439+
const auto filtered_path =
440+
::behavior_velocity_planner::filterLitterPathPoint(to_path(velocity_planned_path));
440441

441442
// interpolation
442-
const auto interpolated_path_msg =
443-
::behavior_velocity_planner::interpolatePath(filtered_path, forward_path_length_, behavior_output_path_interval_);
443+
const auto interpolated_path_msg = ::behavior_velocity_planner::interpolatePath(
444+
filtered_path, forward_path_length_, behavior_output_path_interval_);
444445

445446
// check stop point
446447
output_path_msg = ::behavior_velocity_planner::filterStopPathPoint(interpolated_path_msg);

planning/behavior_velocity_planner/src/node.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -49,11 +49,11 @@ namespace autoware
4949
namespace behavior_velocity_planner
5050
{
5151
using autoware_auto_mapping_msgs::msg::HADMapBin;
52-
using tier4_planning_msgs::msg::VelocityLimit;
53-
using ::behavior_velocity_planner::PlannerData;
5452
using autoware_behavior_velocity_planner::srv::LoadPlugin;
5553
using autoware_behavior_velocity_planner::srv::UnloadPlugin;
54+
using ::behavior_velocity_planner::PlannerData;
5655
using ::behavior_velocity_planner::TrafficSignalStamped;
56+
using tier4_planning_msgs::msg::VelocityLimit;
5757

5858
class BehaviorVelocityPlannerNode : public rclcpp::Node
5959
{

0 commit comments

Comments
 (0)