diff --git a/planning/autoware_behavior_velocity_run_out_module/src/debug.hpp b/planning/autoware_behavior_velocity_run_out_module/src/debug.hpp index 5b7c229f66313..3c6d475950e7c 100644 --- a/planning/autoware_behavior_velocity_run_out_module/src/debug.hpp +++ b/planning/autoware_behavior_velocity_run_out_module/src/debug.hpp @@ -26,10 +26,10 @@ #include namespace autoware::behavior_velocity_planner { +using ::behavior_velocity_planner::Polygon2d; using sensor_msgs::msg::PointCloud2; using tier4_debug_msgs::msg::Float32MultiArrayStamped; using tier4_debug_msgs::msg::Int32Stamped; -using ::behavior_velocity_planner::Polygon2d; class DebugValues { diff --git a/planning/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.cpp b/planning/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.cpp index feccb58beab32..89018bc9cad11 100644 --- a/planning/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.cpp +++ b/planning/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.cpp @@ -32,8 +32,8 @@ namespace autoware::behavior_velocity_planner { -using ::behavior_velocity_planner::splineInterpolate; using ::behavior_velocity_planner::Point2d; +using ::behavior_velocity_planner::splineInterpolate; namespace { // create quaternion facing to the nearest trajectory point diff --git a/planning/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.hpp b/planning/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.hpp index f1c27acaa91ce..5feb07da5a57d 100644 --- a/planning/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.hpp +++ b/planning/autoware_behavior_velocity_run_out_module/src/dynamic_obstacle.hpp @@ -49,12 +49,12 @@ using autoware_auto_perception_msgs::msg::PredictedObjects; using autoware_auto_perception_msgs::msg::Shape; using autoware_auto_planning_msgs::msg::PathPointWithLaneId; using autoware_auto_planning_msgs::msg::PathWithLaneId; +using ::behavior_velocity_planner::PlannerData; using run_out_utils::DynamicObstacle; using run_out_utils::DynamicObstacleData; using run_out_utils::DynamicObstacleParam; using run_out_utils::PlannerParam; using run_out_utils::PredictedPath; -using ::behavior_velocity_planner::PlannerData; using PathPointsWithLaneId = std::vector; using ::behavior_velocity_planner::Polygons2d; diff --git a/planning/autoware_behavior_velocity_run_out_module/src/manager.cpp b/planning/autoware_behavior_velocity_run_out_module/src/manager.cpp index 48c86053b2b32..b99b488241b8f 100644 --- a/planning/autoware_behavior_velocity_run_out_module/src/manager.cpp +++ b/planning/autoware_behavior_velocity_run_out_module/src/manager.cpp @@ -22,8 +22,8 @@ namespace autoware::behavior_velocity_planner { -using tier4_autoware_utils::getOrDeclareParameter; using ::behavior_velocity_planner::SceneModuleManagerInterface; +using tier4_autoware_utils::getOrDeclareParameter; RunOutModuleManager::RunOutModuleManager(rclcpp::Node & node) : SceneModuleManagerInterface(node, getModuleName()) { @@ -204,4 +204,5 @@ void RunOutModuleManager::setDynamicObstacleCreator( #include PLUGINLIB_EXPORT_CLASS( - autoware::behavior_velocity_planner::RunOutModulePlugin, behavior_velocity_planner::PluginInterface) + autoware::behavior_velocity_planner::RunOutModulePlugin, + behavior_velocity_planner::PluginInterface) diff --git a/planning/autoware_behavior_velocity_run_out_module/src/manager.hpp b/planning/autoware_behavior_velocity_run_out_module/src/manager.hpp index c40fc5501e19c..40b86f3636711 100644 --- a/planning/autoware_behavior_velocity_run_out_module/src/manager.hpp +++ b/planning/autoware_behavior_velocity_run_out_module/src/manager.hpp @@ -25,9 +25,9 @@ namespace autoware::behavior_velocity_planner { +using ::behavior_velocity_planner::PluginWrapper; using ::behavior_velocity_planner::SceneModuleInterface; using ::behavior_velocity_planner::SceneModuleManagerInterface; -using ::behavior_velocity_planner::PluginWrapper; class RunOutModuleManager : public SceneModuleManagerInterface { public: diff --git a/planning/autoware_behavior_velocity_run_out_module/src/scene.cpp b/planning/autoware_behavior_velocity_run_out_module/src/scene.cpp index a8bc9b56108ed..d40759512b3d4 100644 --- a/planning/autoware_behavior_velocity_run_out_module/src/scene.cpp +++ b/planning/autoware_behavior_velocity_run_out_module/src/scene.cpp @@ -37,8 +37,8 @@ namespace autoware::behavior_velocity_planner { namespace bg = boost::geometry; -using object_recognition_utils::convertLabelToString; using ::behavior_velocity_planner::PlanningBehavior; +using object_recognition_utils::convertLabelToString; namespace planning_utils = ::behavior_velocity_planner::planning_utils; using ::behavior_velocity_planner::getCrosswalksOnPath; using ::behavior_velocity_planner::Polygon2d; diff --git a/planning/autoware_behavior_velocity_run_out_module/src/scene.hpp b/planning/autoware_behavior_velocity_run_out_module/src/scene.hpp index 230ea3b8c0725..f7bd6fc792faf 100644 --- a/planning/autoware_behavior_velocity_run_out_module/src/scene.hpp +++ b/planning/autoware_behavior_velocity_run_out_module/src/scene.hpp @@ -39,11 +39,11 @@ using run_out_utils::PlannerParam; using run_out_utils::PoseWithRange; using tier4_debug_msgs::msg::Float32Stamped; using BasicPolygons2d = std::vector; -using ::behavior_velocity_planner::SceneModuleInterface; -using ::behavior_velocity_planner::PlannerData; -using ::behavior_velocity_planner::StopReason; using ::behavior_velocity_planner::PathWithLaneId; +using ::behavior_velocity_planner::PlannerData; using ::behavior_velocity_planner::Polygon2d; +using ::behavior_velocity_planner::SceneModuleInterface; +using ::behavior_velocity_planner::StopReason; class RunOutModule : public SceneModuleInterface { diff --git a/planning/autoware_behavior_velocity_run_out_module/src/utils.cpp b/planning/autoware_behavior_velocity_run_out_module/src/utils.cpp index e4635e07b85b1..85dc9b571a53c 100644 --- a/planning/autoware_behavior_velocity_run_out_module/src/utils.cpp +++ b/planning/autoware_behavior_velocity_run_out_module/src/utils.cpp @@ -35,8 +35,8 @@ #include namespace autoware::behavior_velocity_planner { -using ::behavior_velocity_planner::PathPointWithLaneId; using ::behavior_velocity_planner::DetectionRange; +using ::behavior_velocity_planner::PathPointWithLaneId; namespace planning_utils = ::behavior_velocity_planner::planning_utils; namespace run_out_utils { diff --git a/planning/autoware_behavior_velocity_run_out_module/src/utils.hpp b/planning/autoware_behavior_velocity_run_out_module/src/utils.hpp index 81195d5edaaa3..97873ed274cd4 100644 --- a/planning/autoware_behavior_velocity_run_out_module/src/utils.hpp +++ b/planning/autoware_behavior_velocity_run_out_module/src/utils.hpp @@ -39,14 +39,14 @@ using autoware_auto_perception_msgs::msg::PredictedObjects; using autoware_auto_perception_msgs::msg::Shape; using autoware_auto_planning_msgs::msg::PathPoint; using autoware_auto_planning_msgs::msg::PathWithLaneId; +using ::behavior_velocity_planner::PlannerData; +using ::behavior_velocity_planner::Polygons2d; using tier4_autoware_utils::Box2d; using tier4_autoware_utils::LineString2d; using tier4_autoware_utils::Point2d; using tier4_autoware_utils::Polygon2d; using tier4_debug_msgs::msg::Float32Stamped; using vehicle_info_util::VehicleInfo; -using ::behavior_velocity_planner::Polygons2d; -using ::behavior_velocity_planner::PlannerData; using PathPointsWithLaneId = std::vector; struct CommonParam {