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(avoidance): update filtering logic for non-vehicle (#6206) #1121

Merged
merged 1 commit into from
Jan 30, 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
1 change: 1 addition & 0 deletions planning/behavior_path_avoidance_module/src/debug.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -557,6 +557,7 @@ MarkerArray createDebugMarkerArray(
addObjects(data.other_objects, std::string("TooNearToGoal"));
addObjects(data.other_objects, std::string("ParallelToEgoLane"));
addObjects(data.other_objects, std::string("MergingToEgoLane"));
addObjects(data.other_objects, std::string("UnstableObject"));
}

// shift line pre-process
Expand Down
29 changes: 25 additions & 4 deletions planning/behavior_path_avoidance_module/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -368,13 +368,15 @@ bool isSafetyCheckTargetObjectType(
return parameters->object_parameters.at(object_type).is_safety_check_target;
}

bool isVehicleTypeObject(const ObjectData & object)
bool isUnknownTypeObject(const ObjectData & object)
{
const auto object_type = utils::getHighestProbLabel(object.object.classification);
return object_type == ObjectClassification::UNKNOWN;
}

if (object_type == ObjectClassification::UNKNOWN) {
return false;
}
bool isVehicleTypeObject(const ObjectData & object)
{
const auto object_type = utils::getHighestProbLabel(object.object.classification);

if (object_type == ObjectClassification::PEDESTRIAN) {
return false;
Expand Down Expand Up @@ -723,6 +725,15 @@ bool isSatisfiedWithNonVehicleCondition(
return false;
}

// Object is on center line -> ignore.
const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose;
object.to_centerline =
lanelet::utils::getArcCoordinates(data.current_lanelets, object_pose).distance;
if (std::abs(object.to_centerline) < parameters->threshold_distance_object_is_on_center) {
object.reason = AvoidanceDebugFactor::TOO_NEAR_TO_CENTERLINE;
return false;
}

return true;
}

Expand Down Expand Up @@ -1626,6 +1637,16 @@ void filterTargetObjects(
o.to_road_shoulder_distance = filtering_utils::getRoadShoulderDistance(o, data, planner_data);
o.avoid_margin = filtering_utils::getAvoidMargin(o, planner_data, parameters);

// TODO(Satoshi Ota) parametrize stop time threshold if need.
constexpr double STOP_TIME_THRESHOLD = 3.0; // [s]
if (filtering_utils::isUnknownTypeObject(o)) {
if (o.stop_time < STOP_TIME_THRESHOLD) {
o.reason = "UnstableObject";
data.other_objects.push_back(o);
continue;
}
}

if (filtering_utils::isNoNeedAvoidanceBehavior(o, parameters)) {
data.other_objects.push_back(o);
continue;
Expand Down
Loading