Skip to content

Commit d63bec2

Browse files
authored
refactor(goal_planner): refactor goal_searcher and goal_candidates (#10049)
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent 2c53d5f commit d63bec2

File tree

10 files changed

+182
-192
lines changed

10 files changed

+182
-192
lines changed

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/decision_state.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@
1515
#ifndef AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__DECISION_STATE_HPP_
1616
#define AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__DECISION_STATE_HPP_
1717

18-
#include "autoware/behavior_path_goal_planner_module/goal_searcher_base.hpp"
18+
#include "autoware/behavior_path_goal_planner_module/goal_searcher.hpp"
1919
#include "autoware/behavior_path_goal_planner_module/pull_over_planner/pull_over_planner_base.hpp"
2020
#include "autoware/behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp"
2121

@@ -56,7 +56,7 @@ class PathDecisionStateController
5656
const std::shared_ptr<const PlannerData> planner_data,
5757
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
5858
const bool is_current_safe, const GoalPlannerParameters & parameters,
59-
const std::shared_ptr<GoalSearcherBase> goal_searcher, const bool is_activated,
59+
const GoalSearcher & goal_searcher, const bool is_activated,
6060
const std::optional<PullOverPath> & pull_over_path,
6161
std::vector<autoware::universe_utils::Polygon2d> & ego_polygons_expanded);
6262

@@ -77,7 +77,7 @@ class PathDecisionStateController
7777
const std::shared_ptr<const PlannerData> planner_data,
7878
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
7979
const bool is_current_safe, const GoalPlannerParameters & parameters,
80-
const std::shared_ptr<GoalSearcherBase> goal_searcher, const bool is_activated,
80+
const GoalSearcher & goal_searcher, const bool is_activated,
8181
const std::optional<PullOverPath> & pull_over_path_opt,
8282
std::vector<autoware::universe_utils::Polygon2d> & ego_polygons_expanded) const;
8383
};
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,36 @@
1+
// Copyright 2025 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_CANDIDATE_HPP_
16+
#define AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_CANDIDATE_HPP_
17+
18+
#include <geometry_msgs/msg/pose.hpp>
19+
20+
#include <vector>
21+
22+
namespace autoware::behavior_path_planner
23+
{
24+
struct GoalCandidate
25+
{
26+
geometry_msgs::msg::Pose goal_pose{};
27+
double distance_from_original_goal{0.0};
28+
double lateral_offset{0.0};
29+
size_t id{0};
30+
bool is_safe{true};
31+
size_t num_objects_to_avoid{0};
32+
};
33+
using GoalCandidates = std::vector<GoalCandidate>;
34+
35+
} // namespace autoware::behavior_path_planner
36+
#endif // AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_CANDIDATE_HPP_

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_planner_module.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -335,7 +335,7 @@ class GoalPlannerModule : public SceneModuleInterface
335335
std::unique_ptr<FixedGoalPlannerBase> fixed_goal_planner_;
336336

337337
// goal searcher
338-
std::shared_ptr<GoalSearcherBase> goal_searcher_;
338+
std::optional<GoalSearcher> goal_searcher_{};
339339
GoalCandidates goal_candidates_{};
340340

341341
bool use_bus_stop_area_{false};
@@ -364,7 +364,8 @@ class GoalPlannerModule : public SceneModuleInterface
364364
mutable GoalPlannerDebugData debug_data_;
365365

366366
// goal seach
367-
GoalCandidates generateGoalCandidates(const bool use_bus_stop_area) const;
367+
GoalCandidates generateGoalCandidates(
368+
GoalSearcher & goal_searcher, const bool use_bus_stop_area) const;
368369

369370
/*
370371
* state transitions and plan function used in each state
@@ -433,7 +434,6 @@ class GoalPlannerModule : public SceneModuleInterface
433434
std::optional<PullOverPath> selectPullOverPath(
434435
const PullOverContextData & context_data,
435436
const std::vector<PullOverPath> & pull_over_path_candidates,
436-
const GoalCandidates & goal_candidates,
437437
const std::optional<std::vector<size_t>> sorted_bezier_indices_opt) const;
438438

439439
// lanes and drivable area

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher.hpp

+34-11
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,12 @@
1515
#ifndef AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_SEARCHER_HPP_
1616
#define AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__GOAL_SEARCHER_HPP_
1717

18-
#include "autoware/behavior_path_goal_planner_module/goal_searcher_base.hpp"
18+
#include "autoware/behavior_path_goal_planner_module/goal_candidate.hpp"
19+
#include "autoware/behavior_path_goal_planner_module/goal_planner_parameters.hpp"
20+
#include "autoware/behavior_path_planner_common/data_manager.hpp"
21+
#include "autoware/behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp"
22+
23+
#include <geometry_msgs/msg/pose_stamped.hpp>
1924

2025
#include <memory>
2126
#include <vector>
@@ -24,32 +29,45 @@ namespace autoware::behavior_path_planner
2429
{
2530
using autoware::universe_utils::LinearRing2d;
2631
using BasicPolygons2d = std::vector<lanelet::BasicPolygon2d>;
32+
using autoware::universe_utils::MultiPolygon2d;
2733

28-
class GoalSearcher : public GoalSearcherBase
34+
class GoalSearcher
2935
{
3036
public:
31-
GoalSearcher(const GoalPlannerParameters & parameters, const LinearRing2d & vehicle_footprint);
37+
static GoalSearcher create(
38+
const GoalPlannerParameters & parameters, const LinearRing2d & vehicle_footprint,
39+
const std::shared_ptr<const PlannerData> & planner_data);
3240

41+
public:
3342
GoalCandidates search(
34-
const std::shared_ptr<const PlannerData> & planner_data, const bool use_bus_stop_area) override;
43+
const std::shared_ptr<const PlannerData> & planner_data, const bool use_bus_stop_area);
3544
void update(
3645
GoalCandidates & goal_candidates,
3746
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
3847
const std::shared_ptr<const PlannerData> & planner_data,
39-
const PredictedObjects & objects) const override;
48+
const PredictedObjects & objects) const;
4049

4150
// todo(kosuke55): Functions for this specific use should not be in the interface,
4251
// so it is better to consider interface design when we implement other goal searchers.
4352
GoalCandidate getClosetGoalCandidateAlongLanes(
4453
const GoalCandidates & goal_candidates,
45-
const std::shared_ptr<const PlannerData> & planner_data) const override;
54+
const std::shared_ptr<const PlannerData> & planner_data) const;
4655
bool isSafeGoalWithMarginScaleFactor(
4756
const GoalCandidate & goal_candidate, const double margin_scale_factor,
4857
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
4958
const std::shared_ptr<const PlannerData> & planner_data,
50-
const PredictedObjects & objects) const override;
59+
const PredictedObjects & objects) const;
60+
61+
MultiPolygon2d getAreaPolygons() const { return area_polygons_; }
5162

5263
private:
64+
GoalSearcher(
65+
const GoalPlannerParameters & parameters, const LinearRing2d & vehicle_footprint,
66+
const bool left_side_parking, const lanelet::ConstLanelets & pull_over_lanes,
67+
const lanelet::BasicPolygons2d & no_parking_area_polygons,
68+
const lanelet::BasicPolygons2d & no_stopping_area_polygons,
69+
const lanelet::BasicPolygons2d & bus_stop_area_polygons);
70+
5371
void countObjectsToAvoid(
5472
GoalCandidates & goal_candidates, const PredictedObjects & objects,
5573
const std::shared_ptr<const PlannerData> & planner_data,
@@ -64,11 +82,16 @@ class GoalSearcher : public GoalSearcherBase
6482
const Pose & ego_pose, const PredictedObjects & objects,
6583
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
6684
const std::shared_ptr<const PlannerData> & planner_data) const;
67-
BasicPolygons2d getNoParkingAreaPolygons(const lanelet::ConstLanelets & lanes) const;
68-
BasicPolygons2d getNoStoppingAreaPolygons(const lanelet::ConstLanelets & lanes) const;
6985

70-
LinearRing2d vehicle_footprint_{};
71-
bool left_side_parking_{true};
86+
const GoalPlannerParameters parameters_;
87+
const LinearRing2d vehicle_footprint_;
88+
const bool left_side_parking_;
89+
const lanelet::ConstLanelets pull_over_lanes_;
90+
const lanelet::BasicPolygons2d no_parking_area_polygons_;
91+
const lanelet::BasicPolygons2d no_stopping_area_polygons_;
92+
const lanelet::BasicPolygons2d bus_stop_area_polygons_;
93+
94+
MultiPolygon2d area_polygons_{};
7295
};
7396
} // namespace autoware::behavior_path_planner
7497

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/goal_searcher_base.hpp

-75
This file was deleted.

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/pull_over_planner_base.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -14,8 +14,8 @@
1414

1515
#pragma once
1616

17+
#include "autoware/behavior_path_goal_planner_module/goal_candidate.hpp"
1718
#include "autoware/behavior_path_goal_planner_module/goal_planner_parameters.hpp"
18-
#include "autoware/behavior_path_goal_planner_module/goal_searcher_base.hpp"
1919
#include "autoware/behavior_path_planner_common/data_manager.hpp"
2020

2121
#include <geometry_msgs/msg/pose_stamped.hpp>

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/util.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@
1515
#ifndef AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__UTIL_HPP_
1616
#define AUTOWARE__BEHAVIOR_PATH_GOAL_PLANNER_MODULE__UTIL_HPP_
1717

18-
#include "autoware/behavior_path_goal_planner_module/goal_searcher_base.hpp"
18+
#include "autoware/behavior_path_goal_planner_module/goal_candidate.hpp"
1919
#include "autoware/behavior_path_goal_planner_module/pull_over_planner/pull_over_planner_base.hpp"
2020

2121
#include <autoware/lane_departure_checker/lane_departure_checker.hpp>

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/decision_state.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ void PathDecisionStateController::transit_state(
3232
const std::shared_ptr<const PlannerData> planner_data,
3333
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
3434
const bool is_current_safe, const GoalPlannerParameters & parameters,
35-
const std::shared_ptr<GoalSearcherBase> goal_searcher, const bool is_activated,
35+
const GoalSearcher & goal_searcher, const bool is_activated,
3636
const std::optional<PullOverPath> & pull_over_path,
3737
std::vector<autoware::universe_utils::Polygon2d> & ego_polygons_expanded)
3838
{
@@ -50,7 +50,7 @@ PathDecisionState PathDecisionStateController::get_next_state(
5050
const std::shared_ptr<const PlannerData> planner_data,
5151
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
5252
const bool is_current_safe, const GoalPlannerParameters & parameters,
53-
const std::shared_ptr<GoalSearcherBase> goal_searcher, const bool is_activated,
53+
const GoalSearcher & goal_searcher, const bool is_activated,
5454
const std::optional<PullOverPath> & pull_over_path_opt,
5555
std::vector<autoware::universe_utils::Polygon2d> & ego_polygons_expanded) const
5656
{
@@ -105,7 +105,7 @@ PathDecisionState PathDecisionStateController::get_next_state(
105105

106106
// check goal pose collision
107107
if (
108-
modified_goal_opt && !goal_searcher->isSafeGoalWithMarginScaleFactor(
108+
modified_goal_opt && !goal_searcher.isSafeGoalWithMarginScaleFactor(
109109
modified_goal_opt.value(), hysteresis_factor, occupancy_grid_map,
110110
planner_data, static_target_objects)) {
111111
RCLCPP_DEBUG(logger_, "[DecidingPathStatus]: DECIDING->NOT_DECIDED. goal is not safe");

0 commit comments

Comments
 (0)