Skip to content

refactor(lane_change): remove waitApproval dependencies #6052

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

Closed
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 @@ -78,7 +78,7 @@ class AvoidanceModule : public SceneModuleInterface

bool canTransitFailureState() override { return false; }

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

/**
* @brief update RTC status for candidate shift line.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -345,7 +345,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface

bool canTransitFailureState() override { return false; }

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

bool isLabelTargetObstacle(const uint8_t label) const;
void updateTargetObjects();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -330,7 +330,7 @@ class GoalPlannerModule : public SceneModuleInterface
// 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 canTransitIdleToWaitingApprovalState() override { return true; }

mutable StartGoalPlannerData goal_planner_data_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1765,6 +1765,9 @@ void GoalPlannerModule::updateSafetyCheckTargetObjectsData(

std::pair<bool, bool> GoalPlannerModule::isSafePath() const
{
if (!thread_safe_data_.get_pull_over_path()) {
return {false, false};
}
const auto pull_over_path = thread_safe_data_.get_pull_over_path()->getCurrentPath();
const auto & current_pose = planner_data_->self_odometry->pose.pose;
const double current_velocity = std::hypot(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -96,25 +96,6 @@ class LaneChangeInterface : public SceneModuleInterface
TurnSignalInfo getCurrentTurnSignalInfo(
const PathWithLaneId & path, const TurnSignalInfo & original_turn_signal_info);

// TODO(someone): remove this, and use base class function
[[deprecated]] BehaviorModuleOutput run() override
{
updateData();

if (!isWaitingApproval()) {
return plan();
}

// module is waiting approval. Check it.
if (isActivated()) {
RCLCPP_DEBUG(getLogger(), "Was waiting approval, and now approved. Do plan().");
return plan();
} else {
RCLCPP_DEBUG(getLogger(), "keep waiting approval... Do planCandidate().");
return planWaitingApproval();
}
}

protected:
std::shared_ptr<LaneChangeParameters> parameters_;

Expand All @@ -126,7 +107,7 @@ class LaneChangeInterface : public SceneModuleInterface

bool canTransitFailureState() override;

bool canTransitIdleToRunningState() override;
bool canTransitIdleToWaitingApprovalState() override;

void setObjectDebugVisualization() const;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -237,7 +237,7 @@ class LaneChangeBase
LaneChangeStatus status_{};
PathShifter path_shifter_{};

LaneChangeStates current_lane_change_state_{};
LaneChangeStates current_lane_change_state_{LaneChangeStates::Normal};

std::shared_ptr<LaneChangeParameters> lane_change_parameters_{};
std::shared_ptr<LaneChangePath> abort_path_{};
Expand Down
33 changes: 7 additions & 26 deletions planning/behavior_path_lane_change_module/src/interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,10 +49,12 @@ LaneChangeInterface::LaneChangeInterface(

void LaneChangeInterface::processOnEntry()
{
waitApproval();
module_type_->setPreviousModulePaths(
getPreviousModuleOutput().reference_path, getPreviousModuleOutput().path);
module_type_->setPreviousDrivableAreaInfo(getPreviousModuleOutput().drivable_area_info);
module_type_->setPreviousTurnSignalInfo(getPreviousModuleOutput().turn_signal_info);
module_type_->updateLaneChangeStatus();
setObjectDebugVisualization();
}

void LaneChangeInterface::processOnExit()
Expand Down Expand Up @@ -80,13 +82,16 @@ void LaneChangeInterface::updateData()
{
module_type_->setPreviousModulePaths(
getPreviousModuleOutput().reference_path, getPreviousModuleOutput().path);
module_type_->setPreviousDrivableAreaInfo(getPreviousModuleOutput().drivable_area_info);
module_type_->setPreviousTurnSignalInfo(getPreviousModuleOutput().turn_signal_info);
module_type_->updateSpecialData();
module_type_->resetStopPose();
}

void LaneChangeInterface::postProcess()
{
post_process_safety_status_ = module_type_->isApprovedPathSafe();
setObjectDebugVisualization();
}

BehaviorModuleOutput LaneChangeInterface::plan()
Expand All @@ -98,8 +103,6 @@ BehaviorModuleOutput LaneChangeInterface::plan()
return {};
}

module_type_->setPreviousDrivableAreaInfo(getPreviousModuleOutput().drivable_area_info);
module_type_->setPreviousTurnSignalInfo(getPreviousModuleOutput().turn_signal_info);
auto output = module_type_->generateOutput();
path_reference_ = std::make_shared<PathWithLaneId>(output.reference_path);
*prev_approved_path_ = getPreviousModuleOutput().path;
Expand All @@ -112,7 +115,6 @@ BehaviorModuleOutput LaneChangeInterface::plan()
}

updateSteeringFactorPtr(output);
clearWaitingApproval();

return output;
}
Expand All @@ -129,8 +131,6 @@ BehaviorModuleOutput LaneChangeInterface::planWaitingApproval()
out.turn_signal_info = getPreviousModuleOutput().turn_signal_info;
out.drivable_area_info = getPreviousModuleOutput().drivable_area_info;

module_type_->setPreviousModulePaths(
getPreviousModuleOutput().reference_path, getPreviousModuleOutput().path);
module_type_->updateLaneChangeStatus();
setObjectDebugVisualization();

Expand Down Expand Up @@ -226,7 +226,6 @@ bool LaneChangeInterface::canTransitFailureState()
};

log_debug_throttled(__func__);

if (module_type_->isAbortState() && !module_type_->hasFinishedAbort()) {
log_debug_throttled("Abort process has on going.");
return false;
Expand Down Expand Up @@ -293,26 +292,8 @@ bool LaneChangeInterface::canTransitFailureState()
return false;
}

bool LaneChangeInterface::canTransitIdleToRunningState()
bool LaneChangeInterface::canTransitIdleToWaitingApprovalState()
{
setObjectDebugVisualization();

auto log_debug_throttled = [&](std::string_view message) -> void {
RCLCPP_DEBUG(getLogger(), "%s", message.data());
};

log_debug_throttled(__func__);

if (!isActivated() || isWaitingApproval()) {
if (module_type_->specialRequiredCheck()) {
return true;
}
log_debug_throttled("Module is idling.");
return false;
}

log_debug_throttled("Can lane change safely. Executing lane change.");
module_type_->toNormalState();
return true;
}

Expand Down
1 change: 1 addition & 0 deletions planning/behavior_path_lane_change_module/src/scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -420,6 +420,7 @@ void NormalLaneChange::resetParameters()
is_abort_approval_requested_ = false;
current_lane_change_state_ = LaneChangeStates::Normal;
abort_path_ = nullptr;
status_ = {};

object_debug_.clear();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -373,9 +373,9 @@ class SceneModuleInterface
RCLCPP_DEBUG(getLogger(), "%s", message.data());
};
if (current_state_ == ModuleStatus::IDLE) {
if (canTransitIdleToRunningState()) {
if (canTransitIdleToWaitingApprovalState()) {
log_debug_throttled("transiting from IDLE to RUNNING");
return ModuleStatus::RUNNING;
return ModuleStatus::WAITING_APPROVAL;
}

log_debug_throttled("transiting from IDLE to IDLE");
Expand Down Expand Up @@ -462,7 +462,7 @@ class SceneModuleInterface
/**
* @brief State transition condition IDLE -> RUNNING
*/
virtual bool canTransitIdleToRunningState() = 0;
virtual bool canTransitIdleToWaitingApprovalState() = 0;

/**
* @brief Get candidate path. This information is used for external judgement.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ class SideShiftModule : public SceneModuleInterface

bool canTransitFailureState() override { return false; }

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

void initVariables();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -139,7 +139,7 @@ class StartPlannerModule : public SceneModuleInterface

bool canTransitFailureState() override { return false; }

bool canTransitIdleToRunningState() override;
bool canTransitIdleToWaitingApprovalState() override;

/**
* @brief init member variables.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -337,9 +337,9 @@ bool StartPlannerModule::canTransitSuccessState()
return hasFinishedPullOut();
}

bool StartPlannerModule::canTransitIdleToRunningState()
bool StartPlannerModule::canTransitIdleToWaitingApprovalState()
{
return isActivated() && !isWaitingApproval();
return isActivated();
}

BehaviorModuleOutput StartPlannerModule::plan()
Expand Down
Loading