@@ -242,7 +242,7 @@ void categorizeVehicles(
242
242
return ;
243
243
}
244
244
245
- ArcCoordinates getOcclusionPoint (const PredictedObject & obj, const ConstLineString2d & ll_string)
245
+ lanelet:: ArcCoordinates getOcclusionPoint (const PredictedObject & obj, const ConstLineString2d & ll_string)
246
246
{
247
247
const auto poly = tier4_autoware_utils::toPolygon2d (obj);
248
248
std::deque<lanelet::ArcCoordinates> arcs;
@@ -257,14 +257,14 @@ ArcCoordinates getOcclusionPoint(const PredictedObject & obj, const ConstLineStr
257
257
* Ego===============> path
258
258
**/
259
259
// sort by arc length
260
- std::sort (arcs.begin (), arcs.end (), [](ArcCoordinates arc1, ArcCoordinates arc2) {
260
+ std::sort (arcs.begin (), arcs.end (), [](lanelet:: ArcCoordinates arc1, lanelet:: ArcCoordinates arc2) {
261
261
return arc1.length < arc2.length ;
262
262
});
263
263
// remove closest 2 polygon point
264
264
arcs.pop_front ();
265
265
arcs.pop_front ();
266
266
// sort by arc distance
267
- std::sort (arcs.begin (), arcs.end (), [](ArcCoordinates arc1, ArcCoordinates arc2) {
267
+ std::sort (arcs.begin (), arcs.end (), [](lanelet:: ArcCoordinates arc1, lanelet:: ArcCoordinates arc2) {
268
268
return std::abs (arc1.distance ) < std::abs (arc2.distance );
269
269
});
270
270
// return closest to path point which is choosen by farthest 2 points.
@@ -286,11 +286,11 @@ double calcSignedLateralDistanceWithOffset(
286
286
}
287
287
288
288
PossibleCollisionInfo calculateCollisionPathPointFromOcclusionSpot (
289
- const ArcCoordinates & arc_coord_occlusion,
290
- const ArcCoordinates & arc_coord_occlusion_with_offset,
289
+ const lanelet:: ArcCoordinates & arc_coord_occlusion,
290
+ const lanelet:: ArcCoordinates & arc_coord_occlusion_with_offset,
291
291
const lanelet::ConstLanelet & path_lanelet, const PlannerParam & param)
292
292
{
293
- auto calcPosition = [](const ConstLineString2d & ll, const ArcCoordinates & arc) {
293
+ auto calcPosition = [](const ConstLineString2d & ll, const lanelet:: ArcCoordinates & arc) {
294
294
BasicPoint2d bp = fromArcCoordinates (ll, arc);
295
295
Point position;
296
296
position.x = bp[0 ];
@@ -338,8 +338,8 @@ bool generatePossibleCollisionsFromObjects(
338
338
lanelet::ConstLanelet path_lanelet = toPathLanelet (path);
339
339
auto ll = path_lanelet.centerline2d ();
340
340
for (const auto & dyn : dyn_objects) {
341
- ArcCoordinates arc_coord_occlusion = getOcclusionPoint (dyn, ll);
342
- ArcCoordinates arc_coord_occlusion_with_offset = {
341
+ lanelet:: ArcCoordinates arc_coord_occlusion = getOcclusionPoint (dyn, ll);
342
+ lanelet:: ArcCoordinates arc_coord_occlusion_with_offset = {
343
343
arc_coord_occlusion.length - param.baselink_to_front ,
344
344
calcSignedLateralDistanceWithOffset (
345
345
arc_coord_occlusion.distance , param.right_overhang , param.left_overhang ,
@@ -451,7 +451,7 @@ std::optional<PossibleCollisionInfo> generateOneNotableCollisionFromOcclusionSpo
451
451
if (length_to_col < offset_from_start_to_ego) {
452
452
continue ;
453
453
}
454
- ArcCoordinates arc_coord_collision_point = {
454
+ lanelet:: ArcCoordinates arc_coord_collision_point = {
455
455
length_to_col,
456
456
calcSignedLateralDistanceWithOffset (
457
457
arc_coord_occlusion_point.distance , right_overhang, left_overhang, wheel_tread)};
0 commit comments