Skip to content

Commit e0992bb

Browse files
committed
fix
Signed-off-by: veqcc <ryuta.kambe@tier4.jp>
1 parent 720a37c commit e0992bb

File tree

1 file changed

+1
-2
lines changed

1 file changed

+1
-2
lines changed

planning/behavior_velocity_occlusion_spot_module/src/occlusion_spot_utils.cpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -295,8 +295,7 @@ PossibleCollisionInfo calculateCollisionPathPointFromOcclusionSpot(
295295
{
296296
auto calcPosition =
297297
[](const lanelet::ConstLineString2d & ll, const lanelet::ArcCoordinates & arc) {
298-
BasicPoint2d bp = lanelet::geometry::fromArcCoordinates;
299-
(ll, arc);
298+
BasicPoint2d bp = lanelet::geometry::fromArcCoordinates(ll, arc);
300299
Point position;
301300
position.x = bp[0];
302301
position.y = bp[1];

0 commit comments

Comments
 (0)