@@ -951,12 +951,13 @@ std::optional<size_t> getLeadingStaticObjectIdx(
951
951
return leading_obj_idx;
952
952
}
953
953
954
- std::optional< lanelet::BasicPolygon2d> createPolygon (
954
+ lanelet::BasicPolygon2d create_polygon (
955
955
const lanelet::ConstLanelets & lanes, const double start_dist, const double end_dist)
956
956
{
957
957
if (lanes.empty ()) {
958
958
return {};
959
959
}
960
+
960
961
const auto polygon_3d = lanelet::utils::getPolygonFromArcLength (lanes, start_dist, end_dist);
961
962
return lanelet::utils::to2D (polygon_3d).basicPolygon ();
962
963
}
@@ -994,12 +995,11 @@ ExtendedPredictedObject transform(
994
995
return extended_object;
995
996
}
996
997
997
- bool isCollidedPolygonsInLanelet (
998
- const std::vector<Polygon2d> & collided_polygons,
999
- const std::optional<lanelet::BasicPolygon2d> & lanes_polygon)
998
+ bool is_collided_polygons_in_lanelet (
999
+ const std::vector<Polygon2d> & collided_polygons, const lanelet::BasicPolygon2d & lanes_polygon)
1000
1000
{
1001
1001
const auto is_in_lanes = [&](const auto & collided_polygon) {
1002
- return lanes_polygon && boost::geometry::intersects (lanes_polygon. value (), collided_polygon );
1002
+ return ! lanes_polygon. empty () && ! boost::geometry::disjoint (collided_polygon, lanes_polygon );
1003
1003
};
1004
1004
1005
1005
return std::any_of (collided_polygons.begin (), collided_polygons.end (), is_in_lanes);
@@ -1078,28 +1078,28 @@ LanesPolygon create_lanes_polygon(const CommonDataPtr & common_data_ptr)
1078
1078
LanesPolygon lanes_polygon;
1079
1079
1080
1080
lanes_polygon.current =
1081
- utils::lane_change::createPolygon (lanes->current , 0.0 , std::numeric_limits<double >::max ());
1081
+ utils::lane_change::create_polygon (lanes->current , 0.0 , std::numeric_limits<double >::max ());
1082
1082
1083
1083
lanes_polygon.target =
1084
- utils::lane_change::createPolygon (lanes->target , 0.0 , std::numeric_limits<double >::max ());
1084
+ utils::lane_change::create_polygon (lanes->target , 0.0 , std::numeric_limits<double >::max ());
1085
1085
1086
1086
const auto & lc_param_ptr = common_data_ptr->lc_param_ptr ;
1087
1087
const auto expanded_target_lanes = utils::lane_change::generateExpandedLanelets (
1088
1088
lanes->target , common_data_ptr->direction , lc_param_ptr->lane_expansion_left_offset ,
1089
1089
lc_param_ptr->lane_expansion_right_offset );
1090
- lanes_polygon.expanded_target = utils::lane_change::createPolygon (
1090
+ lanes_polygon.expanded_target = utils::lane_change::create_polygon (
1091
1091
expanded_target_lanes, 0.0 , std::numeric_limits<double >::max ());
1092
1092
1093
- lanes_polygon.target_neighbor = * utils::lane_change::createPolygon (
1093
+ lanes_polygon.target_neighbor = utils::lane_change::create_polygon (
1094
1094
lanes->target_neighbor , 0.0 , std::numeric_limits<double >::max ());
1095
1095
1096
1096
lanes_polygon.preceding_target .reserve (lanes->preceding_target .size ());
1097
1097
for (const auto & preceding_lane : lanes->preceding_target ) {
1098
1098
auto lane_polygon =
1099
- utils::lane_change::createPolygon (preceding_lane, 0.0 , std::numeric_limits<double >::max ());
1099
+ utils::lane_change::create_polygon (preceding_lane, 0.0 , std::numeric_limits<double >::max ());
1100
1100
1101
- if (lane_polygon) {
1102
- lanes_polygon.preceding_target .push_back (* lane_polygon);
1101
+ if (! lane_polygon. empty () ) {
1102
+ lanes_polygon.preceding_target .push_back (lane_polygon);
1103
1103
}
1104
1104
}
1105
1105
return lanes_polygon;
@@ -1314,7 +1314,7 @@ bool has_blocking_target_object(
1314
1314
1315
1315
// filtered_objects includes objects out of target lanes, so filter them out
1316
1316
if (boost::geometry::disjoint (
1317
- object.initial_polygon , common_data_ptr->lanes_polygon_ptr ->target . value () )) {
1317
+ object.initial_polygon , common_data_ptr->lanes_polygon_ptr ->target )) {
1318
1318
return false ;
1319
1319
}
1320
1320
@@ -1366,14 +1366,14 @@ bool has_overtaking_turn_lane_object(
1366
1366
}
1367
1367
1368
1368
const auto is_path_overlap_with_target = [&](const LineString2d & path) {
1369
- return !boost::geometry::disjoint (path, common_data_ptr->lanes_polygon_ptr ->target . value () );
1369
+ return !boost::geometry::disjoint (path, common_data_ptr->lanes_polygon_ptr ->target );
1370
1370
};
1371
1371
1372
1372
const auto is_object_overlap_with_target = [&](const auto & object) {
1373
1373
// to compensate for perception issue, or if object is from behind ego, and tries to overtake,
1374
1374
// but stop all of sudden
1375
1375
if (!boost::geometry::disjoint (
1376
- object.initial_polygon , common_data_ptr->lanes_polygon_ptr ->current . value () )) {
1376
+ object.initial_polygon , common_data_ptr->lanes_polygon_ptr ->current )) {
1377
1377
return true ;
1378
1378
}
1379
1379
0 commit comments