File tree 2 files changed +2
-3
lines changed
planning/behavior_velocity_occlusion_spot_module/src
2 files changed +2
-3
lines changed Original file line number Diff line number Diff line change @@ -243,7 +243,7 @@ void categorizeVehicles(
243
243
}
244
244
245
245
lanelet::ArcCoordinates getOcclusionPoint (
246
- const PredictedObject & obj, const ConstLineString2d & ll_string)
246
+ const PredictedObject & obj, const lanelet:: ConstLineString2d & ll_string)
247
247
{
248
248
const auto poly = tier4_autoware_utils::toPolygon2d (obj);
249
249
std::deque<lanelet::ArcCoordinates> arcs;
@@ -293,7 +293,7 @@ PossibleCollisionInfo calculateCollisionPathPointFromOcclusionSpot(
293
293
const lanelet::ArcCoordinates & arc_coord_occlusion_with_offset,
294
294
const lanelet::ConstLanelet & path_lanelet, const PlannerParam & param)
295
295
{
296
- auto calcPosition = [](const ConstLineString2d & ll, const lanelet::ArcCoordinates & arc) {
296
+ auto calcPosition = [](const lanelet:: ConstLineString2d & ll, const lanelet::ArcCoordinates & arc) {
297
297
BasicPoint2d bp = lanelet::geometry::fromArcCoordinates;(ll, arc);
298
298
Point position;
299
299
position.x = bp[0 ];
Original file line number Diff line number Diff line change @@ -60,7 +60,6 @@ using geometry_msgs::msg::Pose;
60
60
using lanelet::BasicLineString2d;
61
61
using lanelet::BasicPoint2d;
62
62
using lanelet::BasicPolygon2d;
63
- using lanelet::ConstLineString2d;
64
63
using lanelet::LaneletMapPtr;
65
64
using DetectionAreaIdx = std::optional<std::pair<double , double >>;
66
65
using BasicPolygons2d = std::vector<lanelet::BasicPolygon2d>;
You can’t perform that action at this time.
0 commit comments