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): revert "refactor(goal_planner): rebuild state transition (#5371)" #5399

Merged
merged 1 commit into from
Oct 25, 2023
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 @@ -217,28 +217,31 @@
}
}

CandidateOutput planCandidate() const override;
BehaviorModuleOutput plan() override;
BehaviorModuleOutput planWaitingApproval() override;
// TODO(someone): remove this, and use base class function
[[deprecated]] BehaviorModuleOutput run() override;
bool isExecutionRequested() const override;
bool isExecutionReady() const override;
// TODO(someone): remove this, and use base class function
[[deprecated]] ModuleStatus updateState() override;
BehaviorModuleOutput plan() override;
BehaviorModuleOutput planWaitingApproval() override;
void processOnEntry() override;
void processOnExit() override;
void updateData() override;
void setParameters(const std::shared_ptr<GoalPlannerParameters> & parameters);
void acceptVisitor(
[[maybe_unused]] const std::shared_ptr<SceneModuleVisitor> & visitor) const override
{
}

// not used, but need to override
CandidateOutput planCandidate() const override { return CandidateOutput{}; };

Check warning on line 237 in planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp#L237

Added line #L237 was not covered by tests

private:
// The start_planner activates when it receives a new route,
// so there is no need to terminate the goal planner.
// If terminating it, it may switch to lane following and could generate an inappropriate path.
bool canTransitSuccessState() override { return false; }

bool canTransitFailureState() override { return false; }

bool canTransitIdleToRunningState() override { return true; }
bool canTransitIdleToRunningState() override { return false; }

Check warning on line 244 in planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/include/behavior_path_planner/scene_module/goal_planner/goal_planner_module.hpp#L244

Added line #L244 was not covered by tests

mutable StartGoalPlannerData goal_planner_data_;

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/src/scene_module/goal_planner/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 1352 to 1367, 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.

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

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Overall Code Complexity

The mean cyclomatic complexity decreases from 4.35 to 4.33, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// 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 @@ -113,13 +113,6 @@
freespace_parking_timer_cb_group_);
}

// Initialize safety checker
if (parameters_->safety_check_params.enable_safety_check) {
initializeSafetyCheckParameters();
utils::start_goal_planner_common::initializeCollisionCheckDebugMap(
goal_planner_data_.collision_check);
}

status_.reset();
}

Expand Down Expand Up @@ -226,18 +219,16 @@
}
}

void GoalPlannerModule::updateData()
BehaviorModuleOutput GoalPlannerModule::run()

Check warning on line 222 in planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp#L222

Added line #L222 was not covered by tests
{
// Initialize Occupancy Grid Map
// This operation requires waiting for `planner_data_`, hence it is executed here instead of in
// the constructor. Ideally, this operation should only need to be performed once.
if (
parameters_->use_occupancy_grid_for_goal_search ||
parameters_->use_occupancy_grid_for_path_collision_check) {
initializeOccupancyGridMap();
current_state_ = ModuleStatus::RUNNING;
updateOccupancyGrid();

Check warning on line 225 in planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp#L224-L225

Added lines #L224 - L225 were not covered by tests

if (!isActivated()) {
return planWaitingApproval();

Check warning on line 228 in planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp#L228

Added line #L228 was not covered by tests
}

updateOccupancyGrid();
return plan();

Check warning on line 231 in planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp#L231

Added line #L231 was not covered by tests
}

void GoalPlannerModule::initializeOccupancyGridMap()
Expand All @@ -264,6 +255,22 @@
objects_filtering_params_, parameters_);
}

void GoalPlannerModule::processOnEntry()
{
// Initialize occupancy grid map
if (
parameters_->use_occupancy_grid_for_goal_search ||
parameters_->use_occupancy_grid_for_path_collision_check) {
initializeOccupancyGridMap();
}
// Initialize safety checker
if (parameters_->safety_check_params.enable_safety_check) {
initializeSafetyCheckParameters();
utils::start_goal_planner_common::initializeCollisionCheckDebugMap(
goal_planner_data_.collision_check);
}
}

void GoalPlannerModule::processOnExit()
{
resetPathCandidate();
Expand Down Expand Up @@ -430,6 +437,13 @@
return refined_goal_pose;
}

ModuleStatus GoalPlannerModule::updateState()

Check warning on line 440 in planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp#L440

Added line #L440 was not covered by tests
{
// start_planner module will be run when setting new goal, so not need finishing pull_over module.
// Finishing it causes wrong lane_following path generation.
return current_state_;

Check warning on line 444 in planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/src/scene_module/goal_planner/goal_planner_module.cpp#L444

Added line #L444 was not covered by tests
}

bool GoalPlannerModule::planFreespacePath()
{
goal_searcher_->setPlannerData(planner_data_);
Expand Down Expand Up @@ -883,12 +897,6 @@
status_.set_has_decided_velocity(true);
}

CandidateOutput GoalPlannerModule::planCandidate() const
{
return CandidateOutput(
status_.get_pull_over_path() ? status_.get_pull_over_path()->getFullPath() : PathWithLaneId());
}

BehaviorModuleOutput GoalPlannerModule::planWithGoalModification()
{
constexpr double path_update_duration = 1.0;
Expand Down Expand Up @@ -927,7 +935,7 @@
// set output and status
BehaviorModuleOutput output{};
setOutput(output);
path_candidate_ = std::make_shared<PathWithLaneId>(planCandidate().path_candidate);
path_candidate_ = std::make_shared<PathWithLaneId>(status_.get_pull_over_path()->getFullPath());
path_reference_ = getPreviousModuleOutput().reference_path;

// return to lane parking if it is possible
Expand Down Expand Up @@ -980,7 +988,10 @@
out.modified_goal = plan().modified_goal; // update status_
out.path = std::make_shared<PathWithLaneId>(generateStopPath());
out.reference_path = getPreviousModuleOutput().reference_path;
path_candidate_ = std::make_shared<PathWithLaneId>(planCandidate().path_candidate);
path_candidate_ =
status_.get_is_safe_static_objects()
? std::make_shared<PathWithLaneId>(status_.get_pull_over_path()->getFullPath())
: out.path;
path_reference_ = getPreviousModuleOutput().reference_path;
const auto distance_to_path_change = calcDistanceToPathChange();

Expand Down
Loading