diff --git a/planning/autoware_behavior_path_external_request_lane_change_module/src/manager.hpp b/planning/autoware_behavior_path_external_request_lane_change_module/src/manager.hpp index 134776b3f2599..414ea3755579c 100644 --- a/planning/autoware_behavior_path_external_request_lane_change_module/src/manager.hpp +++ b/planning/autoware_behavior_path_external_request_lane_change_module/src/manager.hpp @@ -15,8 +15,8 @@ #ifndef MANAGER_HPP_ #define MANAGER_HPP_ -#include "behavior_path_lane_change_module/manager.hpp" #include "autoware_route_handler/autoware_route_handler.hpp" +#include "behavior_path_lane_change_module/manager.hpp" #include diff --git a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/data_manager.hpp b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/data_manager.hpp index 5a73f1776341d..dba3fc3e6f819 100644 --- a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/data_manager.hpp +++ b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/data_manager.hpp @@ -20,11 +20,11 @@ #include "autoware_behavior_path_planner_common/utils/drivable_area_expansion/parameters.hpp" #include "motion_utils/trajectory/trajectory.hpp" +#include #include #include #include #include -#include #include #include @@ -50,6 +50,7 @@ namespace behavior_path_planner { +using autoware::route_handler::RouteHandler; using autoware_adapi_v1_msgs::msg::OperationModeState; using autoware_perception_msgs::msg::PredictedObject; using autoware_perception_msgs::msg::PredictedObjects; @@ -61,7 +62,6 @@ using geometry_msgs::msg::AccelWithCovarianceStamped; using geometry_msgs::msg::PoseStamped; using nav_msgs::msg::OccupancyGrid; using nav_msgs::msg::Odometry; -using autoware::route_handler::RouteHandler; using tier4_planning_msgs::msg::LateralOffset; using tier4_planning_msgs::msg::PathWithLaneId; using PlanResult = PathWithLaneId::SharedPtr; diff --git a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/interface/scene_module_interface.hpp b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/interface/scene_module_interface.hpp index 871000268e7d3..982c8f3f5338f 100644 --- a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/interface/scene_module_interface.hpp +++ b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/interface/scene_module_interface.hpp @@ -22,13 +22,13 @@ #include #include +#include #include #include #include #include #include #include -#include #include #include #include diff --git a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/turn_signal_decider.hpp b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/turn_signal_decider.hpp index 8afd001c0a916..7a6e824a02517 100644 --- a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/turn_signal_decider.hpp +++ b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/turn_signal_decider.hpp @@ -19,8 +19,8 @@ #include #include -#include #include +#include #include #include @@ -42,12 +42,12 @@ namespace behavior_path_planner { +using autoware::route_handler::RouteHandler; using autoware_vehicle_msgs::msg::HazardLightsCommand; using autoware_vehicle_msgs::msg::TurnIndicatorsCommand; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using nav_msgs::msg::Odometry; -using autoware::route_handler::RouteHandler; using tier4_planning_msgs::msg::PathWithLaneId; const std::map g_signal_map = { diff --git a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/utils.hpp b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/utils.hpp index c46507fba7535..c829ec4efa9c9 100644 --- a/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/utils.hpp +++ b/planning/autoware_behavior_path_planner_common/include/autoware_behavior_path_planner_common/utils/utils.hpp @@ -46,10 +46,10 @@ using autoware_perception_msgs::msg::PredictedObject; using autoware_perception_msgs::msg::PredictedObjects; using autoware_perception_msgs::msg::PredictedPath; +using autoware::route_handler::RouteHandler; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Vector3; -using autoware::route_handler::RouteHandler; using tier4_autoware_utils::LinearRing2d; using tier4_autoware_utils::Polygon2d; using tier4_planning_msgs::msg::PathPointWithLaneId; diff --git a/planning/autoware_behavior_path_planner_common/test/test_drivable_area_expansion.cpp b/planning/autoware_behavior_path_planner_common/test/test_drivable_area_expansion.cpp index a5d6c08687d64..37326347d6374 100644 --- a/planning/autoware_behavior_path_planner_common/test/test_drivable_area_expansion.cpp +++ b/planning/autoware_behavior_path_planner_common/test/test_drivable_area_expansion.cpp @@ -228,7 +228,8 @@ TEST(DrivableAreaExpansionProjection, expand_drivable_area) planner_data.dynamic_object = std::make_shared(dynamic_objects); planner_data.self_odometry = std::make_shared(); - planner_data.route_handler = std::make_shared(route_handler); + planner_data.route_handler = + std::make_shared(route_handler); drivable_area_expansion::expand_drivable_area( path, std::make_shared(planner_data)); // unchanged path points diff --git a/planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/data_structs.hpp b/planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/data_structs.hpp index 6bbe34fc4b17c..9f3b66dced8d5 100644 --- a/planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/data_structs.hpp +++ b/planning/autoware_behavior_path_static_obstacle_avoidance_module/include/autoware_behavior_path_static_obstacle_avoidance_module/data_structs.hpp @@ -35,8 +35,8 @@ namespace behavior_path_planner { -using behavior_path_planner::utils::path_safety_checker::CollisionCheckDebug; using autoware::route_handler::Direction; +using behavior_path_planner::utils::path_safety_checker::CollisionCheckDebug; enum class ObjectInfo { NONE = 0, diff --git a/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp index 3487312ffa827..77a83905b20cf 100644 --- a/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp +++ b/planning/autoware_planning_test_manager/include/autoware_planning_test_manager/autoware_planning_test_manager_utils.hpp @@ -14,8 +14,8 @@ #ifndef AUTOWARE_PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_UTILS_HPP_ #define AUTOWARE_PLANNING_TEST_MANAGER__AUTOWARE_PLANNING_TEST_MANAGER_UTILS_HPP_ -#include #include +#include #include #include @@ -26,10 +26,10 @@ namespace autoware_planning_test_manager::utils { +using autoware::route_handler::RouteHandler; using autoware_planning_msgs::msg::LaneletRoute; using geometry_msgs::msg::Pose; using nav_msgs::msg::Odometry; -using autoware::route_handler::RouteHandler; using RouteSections = std::vector; Pose createPoseFromLaneID(const lanelet::Id & lane_id) diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp index 00a368cd46226..f92f652c050dd 100644 --- a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp @@ -15,8 +15,8 @@ #ifndef REMAINING_DISTANCE_TIME_CALCULATOR_NODE_HPP_ #define REMAINING_DISTANCE_TIME_CALCULATOR_NODE_HPP_ -#include #include +#include #include #include diff --git a/planning/autoware_route_handler/test/test_autoware_route_handler.hpp b/planning/autoware_route_handler/test/test_autoware_route_handler.hpp index 0614a6d2d5ea2..e0dd006b40271 100644 --- a/planning/autoware_route_handler/test/test_autoware_route_handler.hpp +++ b/planning/autoware_route_handler/test/test_autoware_route_handler.hpp @@ -20,13 +20,13 @@ #include "planning_test_utils/mock_data_parser.hpp" #include "planning_test_utils/planning_test_utils.hpp" +#include #include #include #include #include #include #include -#include #include diff --git a/planning/autoware_static_centerline_generator/src/type_alias.hpp b/planning/autoware_static_centerline_generator/src/type_alias.hpp index f7d614c4714a9..5b7cd7e12a493 100644 --- a/planning/autoware_static_centerline_generator/src/type_alias.hpp +++ b/planning/autoware_static_centerline_generator/src/type_alias.hpp @@ -28,6 +28,7 @@ namespace autoware::static_centerline_generator { +using autoware::route_handler::RouteHandler; using autoware_map_msgs::msg::LaneletMapBin; using autoware_perception_msgs::msg::PredictedObjects; using autoware_planning_msgs::msg::LaneletRoute; @@ -35,7 +36,6 @@ using autoware_planning_msgs::msg::Path; using autoware_planning_msgs::msg::PathPoint; using autoware_planning_msgs::msg::Trajectory; using autoware_planning_msgs::msg::TrajectoryPoint; -using autoware::route_handler::RouteHandler; using tier4_autoware_utils::LinearRing2d; using tier4_autoware_utils::LineString2d; using tier4_autoware_utils::Point2d; diff --git a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp index 933621cca1fa3..675f364367501 100644 --- a/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp +++ b/planning/behavior_path_avoidance_by_lane_change_module/include/behavior_path_avoidance_by_lane_change_module/manager.hpp @@ -35,8 +35,7 @@ class AvoidanceByLaneChangeModuleManager : public LaneChangeModuleManager public: AvoidanceByLaneChangeModuleManager() : LaneChangeModuleManager( - "avoidance_by_lane_change", Direction::NONE, - LaneChangeModuleType::AVOIDANCE_BY_LANE_CHANGE) + "avoidance_by_lane_change", Direction::NONE, LaneChangeModuleType::AVOIDANCE_BY_LANE_CHANGE) { } diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/manager.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/manager.hpp index d73b7ebcf558b..ef3481bef2e6a 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/manager.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/manager.hpp @@ -16,8 +16,8 @@ #define BEHAVIOR_PATH_LANE_CHANGE_MODULE__MANAGER_HPP_ #include "autoware_behavior_path_planner_common/interface/scene_module_manager_interface.hpp" -#include "behavior_path_lane_change_module/utils/data_structs.hpp" #include "autoware_route_handler/autoware_route_handler.hpp" +#include "behavior_path_lane_change_module/utils/data_structs.hpp" #include @@ -58,8 +58,7 @@ class LaneChangeRightModuleManager : public LaneChangeModuleManager { public: LaneChangeRightModuleManager() - : LaneChangeModuleManager( - "lane_change_right", Direction::RIGHT, LaneChangeModuleType::NORMAL) + : LaneChangeModuleManager("lane_change_right", Direction::RIGHT, LaneChangeModuleType::NORMAL) { } }; @@ -68,8 +67,7 @@ class LaneChangeLeftModuleManager : public LaneChangeModuleManager { public: LaneChangeLeftModuleManager() - : LaneChangeModuleManager( - "lane_change_left", Direction::LEFT, LaneChangeModuleType::NORMAL) + : LaneChangeModuleManager("lane_change_left", Direction::LEFT, LaneChangeModuleType::NORMAL) { } }; diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp index 456fdc6e91187..a5905f8d6ab53 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/scene.hpp @@ -23,6 +23,7 @@ namespace behavior_path_planner { +using autoware::route_handler::Direction; using behavior_path_planner::utils::path_safety_checker::CollisionCheckDebug; using behavior_path_planner::utils::path_safety_checker::CollisionCheckDebugMap; using behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObject; @@ -33,7 +34,6 @@ using data::lane_change::LanesPolygon; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; -using autoware::route_handler::Direction; using tier4_planning_msgs::msg::PathWithLaneId; using utils::path_safety_checker::ExtendedPredictedObjects; diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp index e7e4c154c1151..73c555e379908 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/base_class.hpp @@ -36,11 +36,11 @@ namespace behavior_path_planner { +using autoware::route_handler::Direction; using data::lane_change::PathSafetyStatus; using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; -using autoware::route_handler::Direction; using tier4_autoware_utils::StopWatch; using tier4_planning_msgs::msg::PathWithLaneId; diff --git a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp index 756ec88c97297..034b09816db9b 100644 --- a/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp @@ -38,6 +38,7 @@ namespace behavior_path_planner::utils::lane_change { +using autoware::route_handler::Direction; using autoware_perception_msgs::msg::PredictedObject; using autoware_perception_msgs::msg::PredictedObjects; using autoware_perception_msgs::msg::PredictedPath; @@ -51,7 +52,6 @@ using geometry_msgs::msg::Point; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; using path_safety_checker::CollisionCheckDebugMap; -using autoware::route_handler::Direction; using tier4_autoware_utils::Polygon2d; using tier4_planning_msgs::msg::PathWithLaneId; diff --git a/planning/behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_lane_change_module/src/utils/utils.cpp index 9a49567ba9aaa..7cc7df8c63566 100644 --- a/planning/behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_lane_change_module/src/utils/utils.cpp @@ -57,10 +57,10 @@ namespace behavior_path_planner::utils::lane_change { +using autoware::route_handler::RouteHandler; using autoware_perception_msgs::msg::ObjectClassification; using autoware_perception_msgs::msg::PredictedObjects; using geometry_msgs::msg::Pose; -using autoware::route_handler::RouteHandler; using tier4_autoware_utils::LineString2d; using tier4_autoware_utils::Point2d; using tier4_autoware_utils::Polygon2d; diff --git a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/util.hpp b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/util.hpp index aaa5402d5e0b7..2796c3c145e4f 100644 --- a/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/util.hpp +++ b/planning/behavior_path_start_planner_module/include/behavior_path_start_planner_module/util.hpp @@ -36,12 +36,12 @@ namespace behavior_path_planner::start_planner_utils { +using autoware::route_handler::RouteHandler; using autoware_perception_msgs::msg::PredictedObjects; using autoware_perception_msgs::msg::PredictedPath; using behavior_path_planner::utils::path_safety_checker::EgoPredictedPathParams; using geometry_msgs::msg::Pose; using geometry_msgs::msg::Twist; -using autoware::route_handler::RouteHandler; using tier4_planning_msgs::msg::PathWithLaneId; PathWithLaneId getBackwardPath( diff --git a/planning/behavior_velocity_out_of_lane_module/src/decisions.cpp b/planning/behavior_velocity_out_of_lane_module/src/decisions.cpp index 4905c8d9a44b8..f56cf471fb311 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/decisions.cpp +++ b/planning/behavior_velocity_out_of_lane_module/src/decisions.cpp @@ -62,8 +62,8 @@ bool object_is_incoming( std::optional> object_time_to_range( const autoware_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, - const std::shared_ptr route_handler, const double dist_buffer, - const rclcpp::Logger & logger) + const std::shared_ptr route_handler, + const double dist_buffer, const rclcpp::Logger & logger) { // skip the dynamic object if it is not in a lane preceding the overlapped lane // lane changes are intentionally not considered diff --git a/planning/behavior_velocity_out_of_lane_module/src/decisions.hpp b/planning/behavior_velocity_out_of_lane_module/src/decisions.hpp index c1b1f642419e9..e58ef01d161cf 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/decisions.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/decisions.hpp @@ -17,8 +17,8 @@ #include "types.hpp" -#include #include +#include #include @@ -54,8 +54,8 @@ double time_along_path(const EgoData & ego_data, const size_t target_idx); /// the opposite direction, time at enter > time at exit std::optional> object_time_to_range( const autoware_perception_msgs::msg::PredictedObject & object, const OverlapRange & range, - const std::shared_ptr route_handler, const double dist_buffer, - const rclcpp::Logger & logger); + const std::shared_ptr route_handler, + const double dist_buffer, const rclcpp::Logger & logger); /// @brief use the lanelet map to estimate the times when an object will reach the enter and exit /// points of an overlapping range /// @param [in] object dynamic object diff --git a/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.cpp b/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.cpp index dec1c64731242..a2e4fa475208f 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.cpp +++ b/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.cpp @@ -109,8 +109,8 @@ lanelet::ConstLanelets calculate_ignored_lanelets( lanelet::ConstLanelets calculate_other_lanelets( const EgoData & ego_data, const lanelet::ConstLanelets & path_lanelets, - const lanelet::ConstLanelets & ignored_lanelets, - const RouteHandler & route_handler, const PlannerParam & params) + const lanelet::ConstLanelets & ignored_lanelets, const RouteHandler & route_handler, + const PlannerParam & params) { lanelet::ConstLanelets other_lanelets; const lanelet::BasicPoint2d ego_point(ego_data.pose.position.x, ego_data.pose.position.y); diff --git a/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.hpp b/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.hpp index 1a14aed26172a..1b1c8b583f4a7 100644 --- a/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.hpp +++ b/planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.hpp @@ -68,8 +68,8 @@ lanelet::ConstLanelets calculate_ignored_lanelets( /// @return lanelets to check for overlaps lanelet::ConstLanelets calculate_other_lanelets( const EgoData & ego_data, const lanelet::ConstLanelets & path_lanelets, - const lanelet::ConstLanelets & ignored_lanelets, - const RouteHandler & route_handler, const PlannerParam & params); + const lanelet::ConstLanelets & ignored_lanelets, const RouteHandler & route_handler, + const PlannerParam & params); } // namespace behavior_velocity_planner::out_of_lane #endif // LANELETS_SELECTION_HPP_ diff --git a/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp b/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp index 916775858e1e1..54a52ac91c962 100644 --- a/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp +++ b/planning/mission_planner/src/lanelet2_plugins/default_planner.hpp @@ -15,9 +15,9 @@ #ifndef LANELET2_PLUGINS__DEFAULT_PLANNER_HPP_ #define LANELET2_PLUGINS__DEFAULT_PLANNER_HPP_ +#include #include #include -#include #include #include diff --git a/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp b/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp index 666a634e3d563..1f3b2077cc5eb 100644 --- a/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp +++ b/planning/mission_planner/src/lanelet2_plugins/utility_functions.cpp @@ -42,7 +42,8 @@ void insert_marker_array( } lanelet::ConstLanelet combine_lanelets_with_shoulder( - const lanelet::ConstLanelets & lanelets, const autoware::route_handler::RouteHandler & route_handler) + const lanelet::ConstLanelets & lanelets, + const autoware::route_handler::RouteHandler & route_handler) { lanelet::Points3d lefts; lanelet::Points3d rights; diff --git a/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp b/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp index a26003694a18f..61179d3a996dd 100644 --- a/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp +++ b/planning/mission_planner/src/lanelet2_plugins/utility_functions.hpp @@ -15,8 +15,8 @@ #ifndef LANELET2_PLUGINS__UTILITY_FUNCTIONS_HPP_ #define LANELET2_PLUGINS__UTILITY_FUNCTIONS_HPP_ -#include #include +#include #include #include @@ -54,7 +54,8 @@ void insert_marker_array( * @param route_handler route handler to query the lanelet map */ lanelet::ConstLanelet combine_lanelets_with_shoulder( - const lanelet::ConstLanelets & lanelets, const autoware::route_handler::RouteHandler & route_handler); + const lanelet::ConstLanelets & lanelets, + const autoware::route_handler::RouteHandler & route_handler); std::vector convertCenterlineToPoints(const lanelet::Lanelet & lanelet); geometry_msgs::msg::Pose convertBasicPoint3dToPose( diff --git a/planning/mission_planner/src/mission_planner/mission_planner.hpp b/planning/mission_planner/src/mission_planner/mission_planner.hpp index d85dcce5e9e3c..7242995e21026 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.hpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.hpp @@ -17,10 +17,10 @@ #include "arrival_checker.hpp" +#include #include #include #include -#include #include #include diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.hpp index 32d36fae1ea37..03d3a068352ba 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/decisions.hpp @@ -17,8 +17,8 @@ #include "types.hpp" -#include #include +#include #include diff --git a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/planner_data.hpp b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/planner_data.hpp index d78ce51138e7a..66537db7866e9 100644 --- a/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/planner_data.hpp +++ b/planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware_motion_velocity_planner_common/planner_data.hpp @@ -15,8 +15,8 @@ #ifndef AUTOWARE_MOTION_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_ #define AUTOWARE_MOTION_VELOCITY_PLANNER_COMMON__PLANNER_DATA_HPP_ -#include #include +#include #include #include