Skip to content

Commit b6ad3c0

Browse files
committed
unify lanelet::ConstLineString2d
Signed-off-by: Ryuta Kambe <ryuta.kambe@tier4.jp>
1 parent 6edc7fd commit b6ad3c0

File tree

2 files changed

+2
-3
lines changed

2 files changed

+2
-3
lines changed

planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -243,7 +243,7 @@ void categorizeVehicles(
243243
}
244244

245245
lanelet::ArcCoordinates getOcclusionPoint(
246-
const PredictedObject & obj, const ConstLineString2d & ll_string)
246+
const PredictedObject & obj, const lanelet::ConstLineString2d & ll_string)
247247
{
248248
const auto poly = tier4_autoware_utils::toPolygon2d(obj);
249249
std::deque<lanelet::ArcCoordinates> arcs;
@@ -293,7 +293,7 @@ PossibleCollisionInfo calculateCollisionPathPointFromOcclusionSpot(
293293
const lanelet::ArcCoordinates & arc_coord_occlusion_with_offset,
294294
const lanelet::ConstLanelet & path_lanelet, const PlannerParam & param)
295295
{
296-
auto calcPosition = [](const ConstLineString2d & ll, const lanelet::ArcCoordinates & arc) {
296+
auto calcPosition = [](const lanelet::ConstLineString2d & ll, const lanelet::ArcCoordinates & arc) {
297297
BasicPoint2d bp = lanelet::geometry::fromArcCoordinates;(ll, arc);
298298
Point position;
299299
position.x = bp[0];

planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,6 @@ using geometry_msgs::msg::Pose;
6060
using lanelet::BasicLineString2d;
6161
using lanelet::BasicPoint2d;
6262
using lanelet::BasicPolygon2d;
63-
using lanelet::ConstLineString2d;
6463
using lanelet::LaneletMapPtr;
6564
using DetectionAreaIdx = std::optional<std::pair<double, double>>;
6665
using BasicPolygons2d = std::vector<lanelet::BasicPolygon2d>;

0 commit comments

Comments
 (0)