Skip to content

Commit

Permalink
fix(start_planner): update drivable area info and enable idle to runn…
Browse files Browse the repository at this point in the history
…ing state transition (autowarefoundation#6172)

Update drivable area info and enable idle to running state transition

Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>
  • Loading branch information
kyoichi-sugahara authored and satoshi-ota committed Feb 23, 2024
1 parent 141a80e commit 3b7375a
Show file tree
Hide file tree
Showing 3 changed files with 6 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -1884,6 +1884,10 @@ DrivableAreaInfo combineDrivableAreaInfo(
drivable_area_info1.enable_expanding_intersection_areas ||
drivable_area_info2.enable_expanding_intersection_areas;

// drivable margin
combined_drivable_area_info.drivable_margin =
std::max(drivable_area_info1.drivable_margin, drivable_area_info2.drivable_margin);

return combined_drivable_area_info;
}

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 canTransitIdleToRunningState() override { return true; }

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

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

BehaviorModuleOutput StartPlannerModule::plan()
{
if (isWaitingApproval()) {
Expand Down Expand Up @@ -1318,6 +1313,7 @@ bool StartPlannerModule::planFreespacePath()
void StartPlannerModule::setDrivableAreaInfo(BehaviorModuleOutput & output) const
{
if (status_.planner_type == PlannerType::FREESPACE) {
std::cerr << "Freespace planner updated drivable area." << std::endl;
const double drivable_area_margin = planner_data_->parameters.vehicle_width;
output.drivable_area_info.drivable_margin =
planner_data_->parameters.vehicle_width / 2.0 + drivable_area_margin;
Expand Down

0 comments on commit 3b7375a

Please sign in to comment.