@@ -411,8 +411,8 @@ bool withinRoadLanelet(
411
411
412
412
boost::optional<CrosswalkEdgePoints> isReachableCrosswalkEdgePoints (
413
413
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)
416
416
{
417
417
using Point = boost::geometry::model::d2::point_xy<double >;
418
418
@@ -439,10 +439,10 @@ boost::optional<CrosswalkEdgePoints> isReachableCrosswalkEdgePoints(
439
439
const auto is_stop_object = estimated_velocity < stop_velocity_th;
440
440
const auto velocity = std::max (min_object_vel, estimated_velocity);
441
441
442
- const auto isAcrossAnyRoad = [&surrounding_lanelets, &external_surrounding_crosswalks ](
442
+ const auto isAcrossAnyRoad = [&surrounding_lanelets, &surrounding_crosswalks ](
443
443
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 ) {
446
446
if (boost::geometry::within (p, crosswalk.polygon2d ().basicPolygon ())) {
447
447
return true ;
448
448
}
@@ -1389,18 +1389,17 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser(
1389
1389
lanelet_map_ptr_->laneletLayer , lanelet::BasicPoint2d{obj_pos.x , obj_pos.y },
1390
1390
prediction_time_horizon_.pedestrian * velocity);
1391
1391
lanelet::ConstLanelets surrounding_lanelets;
1392
- lanelet::ConstLanelets external_surrounding_crosswalks ;
1392
+ lanelet::ConstLanelets surrounding_crosswalks ;
1393
1393
for (const auto & [dist, lanelet] : surrounding_lanelets_with_dist) {
1394
1394
surrounding_lanelets.push_back (lanelet);
1395
1395
const auto attr = lanelet.attribute (lanelet::AttributeName::Subtype);
1396
1396
if (
1397
1397
attr.value () == lanelet::AttributeValueString::Crosswalk ||
1398
1398
attr.value () == lanelet::AttributeValueString::Walkway) {
1399
1399
const auto & crosswalk = lanelet;
1400
+ surrounding_crosswalks.push_back (crosswalk);
1400
1401
if (withinLanelet (object, crosswalk)) {
1401
1402
crossing_crosswalk = crosswalk;
1402
- } else {
1403
- external_surrounding_crosswalks.push_back (crosswalk);
1404
1403
}
1405
1404
}
1406
1405
}
@@ -1464,7 +1463,10 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser(
1464
1463
1465
1464
// try to find the edge points for other surrounding crosswalks and generate path to the crosswalk
1466
1465
// 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
+ }
1468
1470
const auto crosswalk_signal_id_opt = getTrafficSignalId (crosswalk);
1469
1471
if (crosswalk_signal_id_opt.has_value () && use_crosswalk_signal_) {
1470
1472
if (!calcIntentionToCrossWithTrafficSignal (
@@ -1489,7 +1491,7 @@ PredictedObject MapBasedPredictionNode::getPredictedObjectAsCrosswalkUser(
1489
1491
}
1490
1492
1491
1493
const auto reachable_crosswalk = isReachableCrosswalkEdgePoints (
1492
- object, surrounding_lanelets, external_surrounding_crosswalks , edge_points,
1494
+ object, surrounding_lanelets, surrounding_crosswalks , edge_points,
1493
1495
prediction_time_horizon_.pedestrian , min_crosswalk_user_velocity_);
1494
1496
1495
1497
if (!reachable_crosswalk) {
0 commit comments