Skip to content

Commit 145f251

Browse files
authored
feat(goal_planner): do not use isActivated() in deciding state transition (#10056)
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent 46ec581 commit 145f251

File tree

3 files changed

+19
-35
lines changed

3 files changed

+19
-35
lines changed

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

+4-8
Original file line numberDiff line numberDiff line change
@@ -49,15 +49,13 @@ class PathDecisionStateController
4949
* @brief update current state and save old current state to prev state
5050
*/
5151
void transit_state(
52-
const bool found_pull_over_path, const rclcpp::Time & now,
52+
const std::optional<PullOverPath> & pull_over_path_opt, const rclcpp::Time & now,
5353
const autoware_perception_msgs::msg::PredictedObjects & static_target_objects,
5454
const autoware_perception_msgs::msg::PredictedObjects & dynamic_target_objects,
55-
const std::optional<GoalCandidate> modified_goal_opt,
5655
const std::shared_ptr<const PlannerData> planner_data,
5756
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
5857
const bool is_current_safe, const GoalPlannerParameters & parameters,
59-
const GoalSearcher & goal_searcher, const bool is_activated,
60-
const std::optional<PullOverPath> & pull_over_path,
58+
const GoalSearcher & goal_searcher,
6159
std::vector<autoware::universe_utils::Polygon2d> & ego_polygons_expanded);
6260

6361
PathDecisionState get_current_state() const { return current_state_; }
@@ -71,14 +69,12 @@ class PathDecisionStateController
7169
* @brief update current state and save old current state to prev state
7270
*/
7371
PathDecisionState get_next_state(
74-
const bool found_pull_over_path, const rclcpp::Time & now,
72+
const std::optional<PullOverPath> & pull_over_path_opt, const rclcpp::Time & now,
7573
const PredictedObjects & static_target_objects, const PredictedObjects & dynamic_target_objects,
76-
const std::optional<GoalCandidate> modified_goal_opt,
7774
const std::shared_ptr<const PlannerData> planner_data,
7875
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
7976
const bool is_current_safe, const GoalPlannerParameters & parameters,
80-
const GoalSearcher & goal_searcher, const bool is_activated,
81-
const std::optional<PullOverPath> & pull_over_path_opt,
77+
const GoalSearcher & goal_searcher,
8278
std::vector<autoware::universe_utils::Polygon2d> & ego_polygons_expanded) const;
8379
};
8480

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/decision_state.cpp

+12-17
Original file line numberDiff line numberDiff line change
@@ -26,32 +26,27 @@ namespace autoware::behavior_path_planner
2626
using autoware::motion_utils::calcSignedArcLength;
2727

2828
void PathDecisionStateController::transit_state(
29-
const bool found_pull_over_path, const rclcpp::Time & now,
29+
const std::optional<PullOverPath> & pull_over_path_opt, const rclcpp::Time & now,
3030
const PredictedObjects & static_target_objects, const PredictedObjects & dynamic_target_objects,
31-
const std::optional<GoalCandidate> modified_goal_opt,
3231
const std::shared_ptr<const PlannerData> planner_data,
3332
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
3433
const bool is_current_safe, const GoalPlannerParameters & parameters,
35-
const GoalSearcher & goal_searcher, const bool is_activated,
36-
const std::optional<PullOverPath> & pull_over_path,
34+
const GoalSearcher & goal_searcher,
3735
std::vector<autoware::universe_utils::Polygon2d> & ego_polygons_expanded)
3836
{
3937
const auto next_state = get_next_state(
40-
found_pull_over_path, now, static_target_objects, dynamic_target_objects, modified_goal_opt,
41-
planner_data, occupancy_grid_map, is_current_safe, parameters, goal_searcher, is_activated,
42-
pull_over_path, ego_polygons_expanded);
38+
pull_over_path_opt, now, static_target_objects, dynamic_target_objects, planner_data,
39+
occupancy_grid_map, is_current_safe, parameters, goal_searcher, ego_polygons_expanded);
4340
current_state_ = next_state;
4441
}
4542

4643
PathDecisionState PathDecisionStateController::get_next_state(
47-
const bool found_pull_over_path, const rclcpp::Time & now,
44+
const std::optional<PullOverPath> & pull_over_path_opt, const rclcpp::Time & now,
4845
const PredictedObjects & static_target_objects, const PredictedObjects & dynamic_target_objects,
49-
const std::optional<GoalCandidate> modified_goal_opt,
5046
const std::shared_ptr<const PlannerData> planner_data,
5147
const std::shared_ptr<OccupancyGridBasedCollisionDetector> occupancy_grid_map,
5248
const bool is_current_safe, const GoalPlannerParameters & parameters,
53-
const GoalSearcher & goal_searcher, const bool is_activated,
54-
const std::optional<PullOverPath> & pull_over_path_opt,
49+
const GoalSearcher & goal_searcher,
5550
std::vector<autoware::universe_utils::Polygon2d> & ego_polygons_expanded) const
5651
{
5752
auto next_state = current_state_;
@@ -77,15 +72,15 @@ PathDecisionState PathDecisionStateController::get_next_state(
7772
}
7873

7974
// if path is not safe, not decided
80-
if (!found_pull_over_path || !pull_over_path_opt) {
75+
if (!pull_over_path_opt) {
8176
next_state.state = PathDecisionState::DecisionKind::NOT_DECIDED;
8277
return next_state;
8378
}
8479

8580
const auto & pull_over_path = pull_over_path_opt.value();
8681
// If it is dangerous against dynamic objects before approval, do not determine the path.
8782
// This eliminates a unsafe path to be approved
88-
if (!next_state.is_stable_safe && !is_activated) {
83+
if (!next_state.is_stable_safe) {
8984
RCLCPP_DEBUG(
9085
logger_,
9186
"[DecidingPathStatus]: NOT_DECIDED. path is not safe against dynamic objects before "
@@ -98,11 +93,11 @@ PathDecisionState PathDecisionStateController::get_next_state(
9893
if (current_state_.state == PathDecisionState::DecisionKind::DECIDING) {
9994
const double hysteresis_factor = 0.9;
10095

96+
const auto & modified_goal = pull_over_path.modified_goal();
10197
// check goal pose collision
102-
if (
103-
modified_goal_opt && !goal_searcher.isSafeGoalWithMarginScaleFactor(
104-
modified_goal_opt.value(), hysteresis_factor, occupancy_grid_map,
105-
planner_data, static_target_objects)) {
98+
if (!goal_searcher.isSafeGoalWithMarginScaleFactor(
99+
modified_goal, hysteresis_factor, occupancy_grid_map, planner_data,
100+
static_target_objects)) {
106101
RCLCPP_DEBUG(logger_, "[DecidingPathStatus]: DECIDING->NOT_DECIDED. goal is not safe");
107102
next_state.state = PathDecisionState::DecisionKind::NOT_DECIDED;
108103
next_state.deciding_start_time = std::nullopt;

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

+3-10
Original file line numberDiff line numberDiff line change
@@ -761,13 +761,6 @@ void GoalPlannerModule::updateData()
761761
? std::make_optional<PullOverPath>(context_data_.value().pull_over_path_opt.value())
762762
: std::nullopt;
763763

764-
const auto modified_goal_pose = [&]() -> std::optional<GoalCandidate> {
765-
if (!pull_over_path_recv) {
766-
return std::nullopt;
767-
}
768-
return pull_over_path_recv.value().modified_goal();
769-
}();
770-
771764
// save "old" state
772765
const auto prev_decision_state = path_decision_controller_.get_current_state();
773766
const auto [is_current_safe, collision_check_map] =
@@ -782,9 +775,9 @@ void GoalPlannerModule::updateData()
782775
dynamic_target_objects, parameters_.th_moving_object_velocity);
783776

784777
path_decision_controller_.transit_state(
785-
found_pull_over_path, clock_->now(), static_target_objects, dynamic_target_objects,
786-
modified_goal_pose, planner_data_, occupancy_grid_map_, is_current_safe, parameters_,
787-
goal_searcher, isActivated(), pull_over_path_recv, debug_data_.ego_polygons_expanded);
778+
pull_over_path_recv, clock_->now(), static_target_objects, dynamic_target_objects,
779+
planner_data_, occupancy_grid_map_, is_current_safe, parameters_, goal_searcher,
780+
debug_data_.ego_polygons_expanded);
788781

789782
auto [lane_parking_response, freespace_parking_response] = syncWithThreads();
790783
if (context_data_) {

0 commit comments

Comments
 (0)