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

feat(avoidance): keep enough distance to avoid object in front of red signal (#6898) #1335

Merged
merged 1 commit into from
Jun 13, 2024
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 @@ -59,6 +59,7 @@ enum class ObjectInfo {
// unavoidable reasons
NEED_DECELERATION,
SAME_DIRECTION_SHIFT,
LIMIT_DRIVABLE_SPACE_TEMPORARY,
INSUFFICIENT_DRIVABLE_SPACE,
INSUFFICIENT_LONGITUDINAL_DISTANCE,
INVALID_SHIFT_LINE,
Expand Down Expand Up @@ -548,6 +549,8 @@ struct AvoidancePlanningData
// nearest object that should be avoid
std::optional<ObjectData> stop_target_object{std::nullopt};

std::optional<lanelet::ConstLanelet> red_signal_lane{std::nullopt};

// new shift point
AvoidLineArray new_shift_line{};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -348,6 +348,11 @@ class AvoidanceHelper
return false;
}

// can avoid it after relax drivable space limitation.
if (object.info == ObjectInfo::LIMIT_DRIVABLE_SPACE_TEMPORARY) {
return false;
}

return true;
}

Expand Down
4 changes: 4 additions & 0 deletions planning/behavior_path_avoidance_module/src/scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -204,6 +204,9 @@ void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugDat
utils::avoidance::isWithinLanes(data.current_lanelets, planner_data_);
const auto red_signal_lane_itr = std::find_if(
data.current_lanelets.begin(), data.current_lanelets.end(), [&](const auto & lanelet) {
if (utils::traffic_light::isTrafficSignalStop({lanelet}, planner_data_)) {
return true;
}
const auto next_lanes = planner_data_->route_handler->getNextLanelets(lanelet);
return utils::traffic_light::isTrafficSignalStop(next_lanes, planner_data_);
});
Expand All @@ -220,6 +223,7 @@ void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugDat
utils::avoidance::generateExpandedDrivableLanes(lanelet, planner_data_, parameters_));
} else {
data.drivable_lanes.push_back(utils::avoidance::generateNotExpandedDrivableLanes(lanelet));
data.red_signal_lane = lanelet;
}
});

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -246,7 +246,13 @@ AvoidOutlines ShiftLineGenerator::generateAvoidOutline(
AvoidOutlines outlines;
for (auto & o : data.target_objects) {
if (!o.avoid_margin.has_value()) {
o.info = ObjectInfo::INSUFFICIENT_DRIVABLE_SPACE;
if (!data.red_signal_lane.has_value()) {
o.info = ObjectInfo::INSUFFICIENT_DRIVABLE_SPACE;
} else if (data.red_signal_lane.value().id() == o.overhang_lanelet.id()) {
o.info = ObjectInfo::LIMIT_DRIVABLE_SPACE_TEMPORARY;
} else {
o.info = ObjectInfo::INSUFFICIENT_DRIVABLE_SPACE;
}
if (o.avoid_required && is_forward_object(o)) {
break;
} else {
Expand Down
Loading