diff --git a/planning/autoware_behavior_velocity_planner/package.xml b/planning/autoware_behavior_velocity_planner/package.xml
index 6587d0e9c7e17..a37e3edd84a66 100644
--- a/planning/autoware_behavior_velocity_planner/package.xml
+++ b/planning/autoware_behavior_velocity_planner/package.xml
@@ -65,6 +65,7 @@
ament_cmake_ros
ament_lint_auto
+ autoware_behavior_velocity_walkway_module
autoware_lint_common
behavior_velocity_blind_spot_module
behavior_velocity_crosswalk_module
@@ -79,7 +80,6 @@
behavior_velocity_stop_line_module
behavior_velocity_traffic_light_module
behavior_velocity_virtual_traffic_light_module
- autoware_behavior_velocity_walkway_module
rosidl_interface_packages
diff --git a/planning/autoware_behavior_velocity_walkway_module/src/manager.cpp b/planning/autoware_behavior_velocity_walkway_module/src/manager.cpp
index aedbddb45b001..1adea85788d5b 100644
--- a/planning/autoware_behavior_velocity_walkway_module/src/manager.cpp
+++ b/planning/autoware_behavior_velocity_walkway_module/src/manager.cpp
@@ -26,12 +26,12 @@
namespace autoware::behavior_velocity_planner
{
+using ::behavior_velocity_planner::SceneModuleManagerInterface;
using lanelet::autoware::Crosswalk;
using tier4_autoware_utils::getOrDeclareParameter;
-using ::behavior_velocity_planner::SceneModuleManagerInterface;
namespace planning_utils = ::behavior_velocity_planner::planning_utils;
-using ::behavior_velocity_planner::getCrosswalksOnPath;
using ::behavior_velocity_planner::getCrosswalkIdSetOnPath;
+using ::behavior_velocity_planner::getCrosswalksOnPath;
WalkwayModuleManager::WalkwayModuleManager(rclcpp::Node & node)
: SceneModuleManagerInterface(node, getModuleName())
@@ -108,4 +108,5 @@ WalkwayModuleManager::getModuleExpiredFunction(const PathWithLaneId & path)
#include
PLUGINLIB_EXPORT_CLASS(
- autoware::behavior_velocity_planner::WalkwayModulePlugin, ::behavior_velocity_planner::PluginInterface)
+ autoware::behavior_velocity_planner::WalkwayModulePlugin,
+ ::behavior_velocity_planner::PluginInterface)
diff --git a/planning/autoware_behavior_velocity_walkway_module/src/manager.hpp b/planning/autoware_behavior_velocity_walkway_module/src/manager.hpp
index c37217adf33da..79b66572062e9 100644
--- a/planning/autoware_behavior_velocity_walkway_module/src/manager.hpp
+++ b/planning/autoware_behavior_velocity_walkway_module/src/manager.hpp
@@ -33,10 +33,10 @@
namespace autoware::behavior_velocity_planner
{
+using autoware_auto_planning_msgs::msg::PathWithLaneId;
using ::behavior_velocity_planner::PluginWrapper;
using ::behavior_velocity_planner::SceneModuleInterface;
using ::behavior_velocity_planner::SceneModuleManagerInterface;
-using autoware_auto_planning_msgs::msg::PathWithLaneId;
class WalkwayModuleManager : public SceneModuleManagerInterface
{
diff --git a/planning/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp b/planning/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp
index 9cc7425b8b981..236654e598216 100644
--- a/planning/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp
+++ b/planning/autoware_behavior_velocity_walkway_module/src/scene_walkway.cpp
@@ -22,18 +22,18 @@
namespace autoware::behavior_velocity_planner
{
namespace bg = boost::geometry;
+using ::behavior_velocity_planner::getLinestringIntersects;
+using ::behavior_velocity_planner::getPolygonIntersects;
+using ::behavior_velocity_planner::getStopLineFromMap;
+using ::behavior_velocity_planner::PlanningBehavior;
+using ::behavior_velocity_planner::SceneModuleInterface;
+using ::behavior_velocity_planner::StopFactor;
+using ::behavior_velocity_planner::VelocityFactor;
using motion_utils::calcLongitudinalOffsetPose;
using motion_utils::calcSignedArcLength;
using motion_utils::findNearestSegmentIndex;
using tier4_autoware_utils::createPoint;
using tier4_autoware_utils::getPose;
-using ::behavior_velocity_planner::PlanningBehavior;
-using ::behavior_velocity_planner::SceneModuleInterface;
-using ::behavior_velocity_planner::StopFactor;
-using ::behavior_velocity_planner::VelocityFactor;
-using ::behavior_velocity_planner::getStopLineFromMap;
-using ::behavior_velocity_planner::getLinestringIntersects;
-using ::behavior_velocity_planner::getPolygonIntersects;
namespace planning_utils = ::behavior_velocity_planner::planning_utils;
WalkwayModule::WalkwayModule(