Skip to content

Commit 3aa3ba2

Browse files
yhisakitechnolojin
authored andcommitted
fix(autoware_map_based_prediction): use surrounding_crosswalks instead of external_surrounding_crosswalks (autowarefoundation#8467)
Signed-off-by: Y.Hisaki <yhisaki31@gmail.com>
1 parent ed28696 commit 3aa3ba2

File tree

1 file changed

+12
-10
lines changed

1 file changed

+12
-10
lines changed

perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp

+12-10
Original file line numberDiff line numberDiff line change
@@ -411,8 +411,8 @@ bool withinRoadLanelet(
411411

412412
boost::optional<CrosswalkEdgePoints> isReachableCrosswalkEdgePoints(
413413
const TrackedObject & object, const lanelet::ConstLanelets & surrounding_lanelets,
414-
const lanelet::ConstLanelets & external_surrounding_crosswalks,
415-
const CrosswalkEdgePoints & edge_points, const double time_horizon, const double min_object_vel)
414+
const lanelet::ConstLanelets & surrounding_crosswalks, const CrosswalkEdgePoints & edge_points,
415+
const double time_horizon, const double min_object_vel)
416416
{
417417
using Point = boost::geometry::model::d2::point_xy<double>;
418418

@@ -439,10 +439,10 @@ boost::optional<CrosswalkEdgePoints> isReachableCrosswalkEdgePoints(
439439
const auto is_stop_object = estimated_velocity < stop_velocity_th;
440440
const auto velocity = std::max(min_object_vel, estimated_velocity);
441441

442-
const auto isAcrossAnyRoad = [&surrounding_lanelets, &external_surrounding_crosswalks](
442+
const auto isAcrossAnyRoad = [&surrounding_lanelets, &surrounding_crosswalks](
443443
const Point & p_src, const Point & p_dst) {
444-
const auto withinAnyCrosswalk = [&external_surrounding_crosswalks](const Point & p) {
445-
for (const auto & crosswalk : external_surrounding_crosswalks) {
444+
const auto withinAnyCrosswalk = [&surrounding_crosswalks](const Point & p) {
445+
for (const auto & crosswalk : surrounding_crosswalks) {
446446
if (boost::geometry::within(p, crosswalk.polygon2d().basicPolygon())) {
447447
return true;
448448
}
@@ -1389,18 +1389,17 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser(
13891389
lanelet_map_ptr_->laneletLayer, lanelet::BasicPoint2d{obj_pos.x, obj_pos.y},
13901390
prediction_time_horizon_.pedestrian * velocity);
13911391
lanelet::ConstLanelets surrounding_lanelets;
1392-
lanelet::ConstLanelets external_surrounding_crosswalks;
1392+
lanelet::ConstLanelets surrounding_crosswalks;
13931393
for (const auto & [dist, lanelet] : surrounding_lanelets_with_dist) {
13941394
surrounding_lanelets.push_back(lanelet);
13951395
const auto attr = lanelet.attribute(lanelet::AttributeName::Subtype);
13961396
if (
13971397
attr.value() == lanelet::AttributeValueString::Crosswalk ||
13981398
attr.value() == lanelet::AttributeValueString::Walkway) {
13991399
const auto & crosswalk = lanelet;
1400+
surrounding_crosswalks.push_back(crosswalk);
14001401
if (withinLanelet(object, crosswalk)) {
14011402
crossing_crosswalk = crosswalk;
1402-
} else {
1403-
external_surrounding_crosswalks.push_back(crosswalk);
14041403
}
14051404
}
14061405
}
@@ -1464,7 +1463,10 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser(
14641463

14651464
// try to find the edge points for other surrounding crosswalks and generate path to the crosswalk
14661465
// edge
1467-
for (const auto & crosswalk : external_surrounding_crosswalks) {
1466+
for (const auto & crosswalk : surrounding_crosswalks) {
1467+
if (crossing_crosswalk && crossing_crosswalk.get() == crosswalk) {
1468+
continue;
1469+
}
14681470
const auto crosswalk_signal_id_opt = getTrafficSignalId(crosswalk);
14691471
if (crosswalk_signal_id_opt.has_value() && use_crosswalk_signal_) {
14701472
if (!calcIntentionToCrossWithTrafficSignal(
@@ -1489,7 +1491,7 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser(
14891491
}
14901492

14911493
const auto reachable_crosswalk = isReachableCrosswalkEdgePoints(
1492-
object, surrounding_lanelets, external_surrounding_crosswalks, edge_points,
1494+
object, surrounding_lanelets, surrounding_crosswalks, edge_points,
14931495
prediction_time_horizon_.pedestrian, min_crosswalk_user_velocity_);
14941496

14951497
if (!reachable_crosswalk) {

0 commit comments

Comments
 (0)