diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp index 5fdef6f467950..ec18d55a31069 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/manager.cpp @@ -183,7 +183,7 @@ bool StartPlannerModuleManager::isSimultaneousExecutableAsApprovedModule() const } // Other modules are not needed when freespace planning - if (start_planner_ptr->isFreespacePlanning()) { + if (module->isFreespacePlanning()) { return false; } @@ -202,7 +202,7 @@ bool StartPlannerModuleManager::isSimultaneousExecutableAsCandidateModule() cons } // Other modules are not needed when freespace planning - if (start_planner_ptr->isFreespacePlanning()) { + if (module->isFreespacePlanning()) { return false; } diff --git a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp index c7541dc8af544..98796d52c6e73 100644 --- a/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp +++ b/planning/behavior_path_planner/src/scene_module/start_planner/start_planner_module.cpp @@ -1026,9 +1026,8 @@ void StartPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) cons output.drivable_area_info.drivable_margin = planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin; } else { - const auto target_drivable_lanes = utils::getNonOverlappingExpandedLanes( - *output.path, generateDrivableLanes(*output.path), - planner_data_->drivable_area_expansion_parameters); + const auto target_drivable_lanes = + getNonOverlappingExpandedLanes(*output.path, generateDrivableLanes(*output.path)); DrivableAreaInfo current_drivable_area_info; current_drivable_area_info.drivable_lanes = target_drivable_lanes;