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(lane_change): fix state transition in lane change for multiple module cooperation #4836

Merged
merged 1 commit into from
Sep 1, 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 @@ -364,16 +364,10 @@ class PlannerManager
* @param planner data.
* @return root lanelet.
*/
lanelet::ConstLanelet updateRootLanelet(
const std::shared_ptr<PlannerData> & data, bool success_lane_change = false) const
lanelet::ConstLanelet updateRootLanelet(const std::shared_ptr<PlannerData> & data) const
satoshi-ota marked this conversation as resolved.
Show resolved Hide resolved
{
lanelet::ConstLanelet ret{};
if (success_lane_change) {
data->route_handler->getClosestPreferredLaneletWithinRoute(
data->self_odometry->pose.pose, &ret);
} else {
data->route_handler->getClosestLaneletWithinRoute(data->self_odometry->pose.pose, &ret);
}
data->route_handler->getClosestLaneletWithinRoute(data->self_odometry->pose.pose, &ret);
RCLCPP_DEBUG(logger_, "update start lanelet. id:%ld", ret.id());
return ret;
}
Expand Down
2 changes: 1 addition & 1 deletion planning/behavior_path_planner/src/planner_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -550,7 +550,7 @@ BehaviorModuleOutput PlannerManager::runApprovedModules(const std::shared_ptr<Pl
[](const auto & m) { return m->name().find("lane_change") != std::string::npos; });

if (success_lane_change) {
root_lanelet_ = updateRootLanelet(data, true);
root_lanelet_ = updateRootLanelet(data);
}

std::for_each(success_module_itr, approved_module_ptrs_.end(), [&](auto & m) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,14 +88,11 @@ ModuleStatus LaneChangeInterface::updateState()
}

if (!module_type_->isValidPath()) {
return ModuleStatus::RUNNING;
return ModuleStatus::SUCCESS;
}

if (module_type_->isAbortState()) {
if (module_type_->hasFinishedAbort()) {
resetLaneChangeModule();
}
return ModuleStatus::RUNNING;
return module_type_->hasFinishedAbort() ? ModuleStatus::SUCCESS : ModuleStatus::RUNNING;
}

if (module_type_->hasFinishedLaneChange()) {
Expand Down Expand Up @@ -154,10 +151,7 @@ ModuleStatus LaneChangeInterface::updateState()
getLogger().get_child(module_type_->getModuleTypeStr()), *clock_, 5000,
"Lane change path is unsafe. Cancel lane change.");
module_type_->toCancelState();
if (!isWaitingApproval()) {
resetLaneChangeModule();
}
return ModuleStatus::RUNNING;
return isWaitingApproval() ? ModuleStatus::RUNNING : ModuleStatus::SUCCESS;
}

if (!module_type_->isAbortEnabled()) {
Expand Down Expand Up @@ -192,13 +186,6 @@ ModuleStatus LaneChangeInterface::updateState()
return ModuleStatus::RUNNING;
}

void LaneChangeInterface::resetLaneChangeModule()
{
processOnExit();
removeRTCStatus();
processOnEntry();
}

void LaneChangeInterface::updateData()
{
module_type_->setPreviousModulePaths(
Expand Down