diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp index 9dad3681f7570..aed8066ef30af 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp @@ -18,6 +18,7 @@ #include "autoware/behavior_path_goal_planner_module/decision_state.hpp" #include "autoware/behavior_path_goal_planner_module/fixed_goal_planner_base.hpp" #include "autoware/behavior_path_goal_planner_module/goal_planner_parameters.hpp" +#include "autoware/behavior_path_goal_planner_module/pull_over_planner/freespace_pull_over.hpp" #include "autoware/behavior_path_goal_planner_module/thread_data.hpp" #include "autoware/behavior_path_planner_common/utils/parking_departure/common_module_data.hpp" #include "autoware/behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp" @@ -151,7 +152,7 @@ bool checkOccupancyGridCollision( // freespace parking std::optional planFreespacePath( const FreespaceParkingRequest & req, const PredictedObjects & static_target_objects, - std::shared_ptr freespace_planner); + std::shared_ptr freespace_planner); bool isStopped( std::deque & odometry_buffer, @@ -198,7 +199,7 @@ class FreespaceParkingPlanner std::mutex & freespace_parking_mutex, const std::optional & request, FreespaceParkingResponse & response, std::atomic & is_freespace_parking_cb_running, const rclcpp::Logger & logger, const rclcpp::Clock::SharedPtr clock, - const std::shared_ptr freespace_planner) + const std::shared_ptr freespace_planner) : mutex_(freespace_parking_mutex), request_(request), response_(response), @@ -218,7 +219,7 @@ class FreespaceParkingPlanner rclcpp::Logger logger_; rclcpp::Clock::SharedPtr clock_; - std::shared_ptr freespace_planner_; + std::shared_ptr freespace_planner_; bool isStuck( const PredictedObjects & static_target_objects, const PredictedObjects & dynamic_target_objects, diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/freespace_pull_over.hpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/freespace_pull_over.hpp index ee370fd96b9a0..e32488965f69a 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/freespace_pull_over.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/freespace_pull_over.hpp @@ -36,6 +36,8 @@ class FreespacePullOver : public PullOverPlannerBase PullOverPlannerType getPlannerType() const override { return PullOverPlannerType::FREESPACE; } + void setMap(const nav_msgs::msg::OccupancyGrid & costmap) { planner_->setMap(costmap); } + std::optional plan( const GoalCandidate & modified_goal_pose, const size_t id, const std::shared_ptr planner_data, diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp index 28a2f8cee48b0..514138c78f091 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp @@ -16,7 +16,6 @@ #include "autoware/behavior_path_goal_planner_module/default_fixed_goal_planner.hpp" #include "autoware/behavior_path_goal_planner_module/goal_searcher.hpp" -#include "autoware/behavior_path_goal_planner_module/pull_over_planner/freespace_pull_over.hpp" #include "autoware/behavior_path_goal_planner_module/pull_over_planner/geometric_pull_over.hpp" #include "autoware/behavior_path_goal_planner_module/pull_over_planner/pull_over_planner_base.hpp" #include "autoware/behavior_path_goal_planner_module/pull_over_planner/shift_pull_over.hpp" @@ -225,7 +224,7 @@ bool checkOccupancyGridCollision( std::optional planFreespacePath( const FreespaceParkingRequest & req, const PredictedObjects & static_target_objects, - std::shared_ptr freespace_planner) + std::shared_ptr freespace_planner) { auto goal_candidates = req.goal_candidates_; auto goal_searcher = std::make_shared(req.parameters_, req.vehicle_footprint_); @@ -238,8 +237,8 @@ std::optional planFreespacePath( if (!goal_candidate.is_safe) { continue; } - // TODO(soblin): this calls setMap() in freespace_planner in the for-loop, which is very - // inefficient + + freespace_planner->setMap(*(req.get_planner_data()->costmap)); const auto freespace_path = freespace_planner->plan( goal_candidate, 0, req.get_planner_data(), BehaviorModuleOutput{} // NOTE: not used so passing {} is OK diff --git a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/freespace_pull_over.cpp b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/freespace_pull_over.cpp index b51d5df42c75b..5b11d1b170ce1 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/freespace_pull_over.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/freespace_pull_over.cpp @@ -64,8 +64,6 @@ std::optional FreespacePullOver::plan( { const Pose & current_pose = planner_data->self_odometry->pose.pose; - planner_->setMap(*planner_data->costmap); - // offset goal pose to make straight path near goal for improving parking precision // todo: support straight path when using back constexpr double straight_distance = 1.0;