From 851e1b76a3400ec857c039a99852c89dc7208568 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 14 May 2024 05:17:50 +0000 Subject: [PATCH] style(pre-commit): autofix --- .../autoware_planning_test_manager_utils.hpp | 16 +++++++++------- .../src/autoware_planning_test_manager.cpp | 3 +-- 2 files changed, 10 insertions(+), 9 deletions(-) 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 aa4bfe9331483..703c042f3b65c 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,18 +14,19 @@ #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 -#include +#include +#include namespace autoware_planning_test_manager::utils { -using route_handler::RouteHandler; -using nav_msgs::msg::Odometry; -using geometry_msgs::msg::Pose; using autoware_planning_msgs::msg::LaneletRoute; +using geometry_msgs::msg::Pose; +using nav_msgs::msg::Odometry; +using route_handler::RouteHandler; using RouteSections = std::vector; Pose createPoseFromLaneID(const lanelet::Id & lane_id) @@ -92,7 +93,8 @@ LaneletRoute makeBehaviorRouteFromLaneId(const int & start_lane_id, const int & // create local route sections route_handler->setRouteLanelets(path_lanelets); const auto local_route_sections = route_handler->createMapSegments(path_lanelets); - route_sections = test_utils::combineConsecutiveRouteSections(route_sections, local_route_sections); + route_sections = + test_utils::combineConsecutiveRouteSections(route_sections, local_route_sections); for (const auto & route_section : route_sections) { for (const auto & primitive : route_section.primitives) { std::cerr << "primitive: " << primitive.id << std::endl; diff --git a/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp b/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp index 96c8c4a1c390a..9ee162ec02d1f 100644 --- a/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp +++ b/planning/autoware_planning_test_manager/src/autoware_planning_test_manager.cpp @@ -16,9 +16,8 @@ #include #include -#include - #include +#include namespace planning_test_utils {