Skip to content

Commit 0db40ae

Browse files
authored
fix(avoidance): update filtering logic for non-vehicle (#6206)
Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent 4c3ea87 commit 0db40ae

File tree

2 files changed

+26
-4
lines changed

2 files changed

+26
-4
lines changed

planning/behavior_path_avoidance_module/src/debug.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -557,6 +557,7 @@ MarkerArray createDebugMarkerArray(
557557
addObjects(data.other_objects, std::string("TooNearToGoal"));
558558
addObjects(data.other_objects, std::string("ParallelToEgoLane"));
559559
addObjects(data.other_objects, std::string("MergingToEgoLane"));
560+
addObjects(data.other_objects, std::string("UnstableObject"));
560561
}
561562

562563
// shift line pre-process

planning/behavior_path_avoidance_module/src/utils.cpp

+25-4
Original file line numberDiff line numberDiff line change
@@ -368,13 +368,15 @@ bool isSafetyCheckTargetObjectType(
368368
return parameters->object_parameters.at(object_type).is_safety_check_target;
369369
}
370370

371-
bool isVehicleTypeObject(const ObjectData & object)
371+
bool isUnknownTypeObject(const ObjectData & object)
372372
{
373373
const auto object_type = utils::getHighestProbLabel(object.object.classification);
374+
return object_type == ObjectClassification::UNKNOWN;
375+
}
374376

375-
if (object_type == ObjectClassification::UNKNOWN) {
376-
return false;
377-
}
377+
bool isVehicleTypeObject(const ObjectData & object)
378+
{
379+
const auto object_type = utils::getHighestProbLabel(object.object.classification);
378380

379381
if (object_type == ObjectClassification::PEDESTRIAN) {
380382
return false;
@@ -723,6 +725,15 @@ bool isSatisfiedWithNonVehicleCondition(
723725
return false;
724726
}
725727

728+
// Object is on center line -> ignore.
729+
const auto & object_pose = object.object.kinematics.initial_pose_with_covariance.pose;
730+
object.to_centerline =
731+
lanelet::utils::getArcCoordinates(data.current_lanelets, object_pose).distance;
732+
if (std::abs(object.to_centerline) < parameters->threshold_distance_object_is_on_center) {
733+
object.reason = AvoidanceDebugFactor::TOO_NEAR_TO_CENTERLINE;
734+
return false;
735+
}
736+
726737
return true;
727738
}
728739

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

1640+
// TODO(Satoshi Ota) parametrize stop time threshold if need.
1641+
constexpr double STOP_TIME_THRESHOLD = 3.0; // [s]
1642+
if (filtering_utils::isUnknownTypeObject(o)) {
1643+
if (o.stop_time < STOP_TIME_THRESHOLD) {
1644+
o.reason = "UnstableObject";
1645+
data.other_objects.push_back(o);
1646+
continue;
1647+
}
1648+
}
1649+
16291650
if (filtering_utils::isNoNeedAvoidanceBehavior(o, parameters)) {
16301651
data.other_objects.push_back(o);
16311652
continue;

0 commit comments

Comments
 (0)