From 744d48d0e3aaf9693062b44eb4c1edabc9659f6b Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Thu, 12 Oct 2023 23:05:31 +0900 Subject: [PATCH] refactor(behavior_path_planner): remove planner data unused variable (#5194) refactor(behavior_path_planner): remove planner data used variable Signed-off-by: Zulfaqar Azmi --- .../include/behavior_path_planner/data_manager.hpp | 2 -- .../behavior_path_planner/test/test_drivable_area_expansion.cpp | 1 - 2 files changed, 3 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/data_manager.hpp b/planning/behavior_path_planner/include/behavior_path_planner/data_manager.hpp index 0a7b59d52ff5a..7f1648c463097 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/data_manager.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/data_manager.hpp @@ -141,11 +141,9 @@ struct PlannerData OccupancyGrid::ConstSharedPtr costmap{}; LateralOffset::ConstSharedPtr lateral_offset{}; OperationModeState::ConstSharedPtr operation_mode{}; - PathWithLaneId::SharedPtr reference_path{std::make_shared()}; PathWithLaneId::SharedPtr prev_output_path{std::make_shared()}; std::optional prev_modified_goal{}; std::optional prev_route_id{}; - lanelet::ConstLanelets current_lanes{}; std::shared_ptr route_handler{std::make_shared()}; BehaviorPathPlannerParameters parameters{}; drivable_area_expansion::DrivableAreaExpansionParameters drivable_area_expansion_parameters{}; diff --git a/planning/behavior_path_planner/test/test_drivable_area_expansion.cpp b/planning/behavior_path_planner/test/test_drivable_area_expansion.cpp index e0a16089b8d84..163221951d726 100644 --- a/planning/behavior_path_planner/test/test_drivable_area_expansion.cpp +++ b/planning/behavior_path_planner/test/test_drivable_area_expansion.cpp @@ -270,7 +270,6 @@ TEST(DrivableAreaExpansionProjection, expandDrivableArea) } behavior_path_planner::PlannerData planner_data; planner_data.drivable_area_expansion_parameters = params; - planner_data.reference_path = std::make_shared(path); planner_data.dynamic_object = std::make_shared(dynamic_objects); planner_data.route_handler = std::make_shared(route_handler);