Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(goal_planner): fix parking_path curvature and DecidingState transition #9022

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -35,15 +35,15 @@ class PathDecisionState
};

DecisionKind state{DecisionKind::NOT_DECIDED};
rclcpp::Time stamp{};
std::optional<rclcpp::Time> deciding_start_time{std::nullopt};
bool is_stable_safe{false};
std::optional<rclcpp::Time> safe_start_time{std::nullopt};
};

class PathDecisionStateController
{
public:
PathDecisionStateController() = default;
explicit PathDecisionStateController(rclcpp::Logger logger) : logger_(logger) {}

/**
* @brief update current state and save old current state to prev state
Expand All @@ -62,11 +62,10 @@ class PathDecisionStateController

PathDecisionState get_current_state() const { return current_state_; }

PathDecisionState get_prev_state() const { return prev_state_; }

private:
rclcpp::Logger logger_;

PathDecisionState current_state_{};
PathDecisionState prev_state_{};

/**
* @brief update current state and save old current state to prev state
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Only prev_state_.stamp was used for saving the time when DECIDING state started.
So I deleted prev_state_ and save deciding_start_time instead.

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -321,7 +321,7 @@ class GoalPlannerModule : public SceneModuleInterface
// context_data_ is initialized in updateData(), used in plan() and refreshed in postProcess()
std::optional<PullOverContextData> context_data_{std::nullopt};
// path_decision_controller is updated in updateData(), and used in plan()
PathDecisionStateController path_decision_controller_{};
PathDecisionStateController path_decision_controller_{getLogger()};
std::unique_ptr<LastApprovalData> last_approval_data_{nullptr};

// approximate distance from the start point to the end point of pull_over.
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 Tier IV, Inc.

Check notice on line 1 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Lines of Code in a Single File

The lines of code increases from 1997 to 2017, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -2643,7 +2643,6 @@
found_pull_over_path, now, static_target_objects, dynamic_target_objects, modified_goal_opt,
planner_data, occupancy_grid_map, is_current_safe, parameters, goal_searcher, is_activated,
pull_over_path, ego_polygons_expanded);
prev_state_ = current_state_;
current_state_ = next_state;
}

Expand All @@ -2658,10 +2657,7 @@
const std::optional<PullOverPath> & pull_over_path_opt,
std::vector<Polygon2d> & ego_polygons_expanded) const
{
auto next_state = prev_state_;

// update timestamp
next_state.stamp = now;
auto next_state = current_state_;

Check warning on line 2660 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp#L2660

Added line #L2660 was not covered by tests

// update safety
if (!parameters.safety_check_params.enable_safety_check) {
Expand All @@ -2684,7 +2680,6 @@

// Once this function returns true, it will continue to return true thereafter
if (next_state.state == PathDecisionState::DecisionKind::DECIDED) {
next_state.state = PathDecisionState::DecisionKind::DECIDED;
return next_state;
}

Expand All @@ -2699,20 +2694,26 @@
// If it is dangerous against dynamic objects before approval, do not determine the path.
// This eliminates a unsafe path to be approved
if (enable_safety_check && !next_state.is_stable_safe && !is_activated) {
RCLCPP_DEBUG(
logger_,
"[DecidingPathStatus]: NOT_DECIDED. path is not safe against dynamic objects before "
"approval");
next_state.state = PathDecisionState::DecisionKind::NOT_DECIDED;
return next_state;
}

const auto & current_path = pull_over_path.getCurrentPath();
if (prev_state_.state == PathDecisionState::DecisionKind::DECIDING) {
if (current_state_.state == PathDecisionState::DecisionKind::DECIDING) {
const double hysteresis_factor = 0.9;

// check goal pose collision
if (
modified_goal_opt && !goal_searcher->isSafeGoalWithMarginScaleFactor(
modified_goal_opt.value(), hysteresis_factor, occupancy_grid_map,
planner_data, static_target_objects)) {
RCLCPP_DEBUG(logger_, "[DecidingPathStatus]: DECIDING->NOT_DECIDED. goal is not safe");
next_state.state = PathDecisionState::DecisionKind::NOT_DECIDED;
next_state.deciding_start_time = std::nullopt;
return next_state;
}

Expand All @@ -2727,24 +2728,36 @@
/*extract_static_objects=*/false, parameters.maximum_deceleration,
parameters.object_recognition_collision_check_max_extra_stopping_margin,
ego_polygons_expanded, true)) {
RCLCPP_DEBUG(
logger_, "[DecidingPathStatus]: DECIDING->NOT_DECIDED. path has collision with objects");
next_state.state = PathDecisionState::DecisionKind::NOT_DECIDED;
next_state.deciding_start_time = std::nullopt;
return next_state;
}

if (enable_safety_check && !next_state.is_stable_safe) {
RCLCPP_DEBUG(
logger_,
"[DecidingPathStatus]: DECIDING->NOT_DECIDED. path is not safe against dynamic objects");
next_state.state = PathDecisionState::DecisionKind::NOT_DECIDED;
return next_state;
}

// if enough time has passed since deciding status starts, transition to DECIDED
constexpr double check_collision_duration = 1.0;
const double elapsed_time_from_deciding = (now - prev_state_.stamp).seconds();
const double elapsed_time_from_deciding =
(now - current_state_.deciding_start_time.value()).seconds();
if (elapsed_time_from_deciding > check_collision_duration) {
RCLCPP_DEBUG(logger_, "[DecidingPathStatus]: DECIDING->DECIDED. has enough safe time passed");
next_state.state = PathDecisionState::DecisionKind::DECIDED;
next_state.deciding_start_time = std::nullopt;
return next_state;
}

// if enough time has NOT passed since deciding status starts, keep DECIDING
RCLCPP_DEBUG(
logger_, "[DecidingPathStatus]: keep DECIDING. elapsed_time_from_deciding: %f",
elapsed_time_from_deciding);
return next_state;
}

Expand All @@ -2766,10 +2779,15 @@
// if object recognition for path collision check is enabled, transition to DECIDING to check
// collision for a certain period of time. Otherwise, transition to DECIDED directly.
if (parameters.use_object_recognition) {
next_state.state = PathDecisionState::DecisionKind::DECIDED;
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In prior PR, I mistakenly changed the next state to DECIDED. DECIDING is correct for this case.

RCLCPP_DEBUG(
logger_,
"[DecidingPathStatus]: NOT_DECIDED->DECIDING. start checking collision for certain "
"period of time");
next_state.state = PathDecisionState::DecisionKind::DECIDING;

Check warning on line 2786 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp#L2786

Added line #L2786 was not covered by tests
next_state.deciding_start_time = now;
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

fixedto return DECIDING as the next state.

return next_state;
}
return {PathDecisionState::DecisionKind::DECIDED, now};
return {PathDecisionState::DecisionKind::DECIDED, std::nullopt};

Check warning on line 2790 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

PathDecisionStateController::get_next_state already has high cyclomatic complexity, and now it increases in Lines of Code from 96 to 117. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.

Check warning on line 2790 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp#L2790

Added line #L2790 was not covered by tests
}

} // namespace autoware::behavior_path_planner
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ std::optional<PullOverPath> PullOverPath::create(
double parking_path_max_curvature{};
std::tie(full_path_curvatures, full_path_max_curvature) = calculateCurvaturesAndMax(full_path);
std::tie(parking_path_curvatures, parking_path_max_curvature) =
calculateCurvaturesAndMax(full_path);
calculateCurvaturesAndMax(parking_path);

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I was using full_path for calculating the curvature of parking_path by mistake

return PullOverPath(
type, goal_id, id, start_pose, end_pose, partial_paths, full_path, parking_path,
Expand Down
Loading