Skip to content

Commit f9ccf6f

Browse files
committed
unify lanelet::ArcCoordinates
Signed-off-by: Ryuta Kambe <ryuta.kambe@tier4.jp>
1 parent a745412 commit f9ccf6f

File tree

2 files changed

+9
-10
lines changed

2 files changed

+9
-10
lines changed

planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp

+9-9
Original file line numberDiff line numberDiff line change
@@ -242,7 +242,7 @@ void categorizeVehicles(
242242
return;
243243
}
244244

245-
ArcCoordinates getOcclusionPoint(const PredictedObject & obj, const ConstLineString2d & ll_string)
245+
lanelet::ArcCoordinates getOcclusionPoint(const PredictedObject & obj, const ConstLineString2d & ll_string)
246246
{
247247
const auto poly = tier4_autoware_utils::toPolygon2d(obj);
248248
std::deque<lanelet::ArcCoordinates> arcs;
@@ -257,14 +257,14 @@ ArcCoordinates getOcclusionPoint(const PredictedObject & obj, const ConstLineStr
257257
* Ego===============> path
258258
**/
259259
// 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) {
261261
return arc1.length < arc2.length;
262262
});
263263
// remove closest 2 polygon point
264264
arcs.pop_front();
265265
arcs.pop_front();
266266
// 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) {
268268
return std::abs(arc1.distance) < std::abs(arc2.distance);
269269
});
270270
// return closest to path point which is choosen by farthest 2 points.
@@ -286,11 +286,11 @@ double calcSignedLateralDistanceWithOffset(
286286
}
287287

288288
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,
291291
const lanelet::ConstLanelet & path_lanelet, const PlannerParam & param)
292292
{
293-
auto calcPosition = [](const ConstLineString2d & ll, const ArcCoordinates & arc) {
293+
auto calcPosition = [](const ConstLineString2d & ll, const lanelet::ArcCoordinates & arc) {
294294
BasicPoint2d bp = fromArcCoordinates(ll, arc);
295295
Point position;
296296
position.x = bp[0];
@@ -338,8 +338,8 @@ bool generatePossibleCollisionsFromObjects(
338338
lanelet::ConstLanelet path_lanelet = toPathLanelet(path);
339339
auto ll = path_lanelet.centerline2d();
340340
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 = {
343343
arc_coord_occlusion.length - param.baselink_to_front,
344344
calcSignedLateralDistanceWithOffset(
345345
arc_coord_occlusion.distance, param.right_overhang, param.left_overhang,
@@ -451,7 +451,7 @@ std::optional<PossibleCollisionInfo> generateOneNotableCollisionFromOcclusionSpo
451451
if (length_to_col < offset_from_start_to_ego) {
452452
continue;
453453
}
454-
ArcCoordinates arc_coord_collision_point = {
454+
lanelet::ArcCoordinates arc_coord_collision_point = {
455455
length_to_col,
456456
calcSignedLateralDistanceWithOffset(
457457
arc_coord_occlusion_point.distance, right_overhang, left_overhang, wheel_tread)};

planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,6 @@ using autoware_auto_planning_msgs::msg::PathPointWithLaneId;
5757
using autoware_auto_planning_msgs::msg::PathWithLaneId;
5858
using geometry_msgs::msg::Point;
5959
using geometry_msgs::msg::Pose;
60-
using lanelet::ArcCoordinates;
6160
using lanelet::BasicLineString2d;
6261
using lanelet::BasicPoint2d;
6362
using lanelet::BasicPolygon2d;

0 commit comments

Comments
 (0)