@@ -331,12 +331,36 @@ bool isWithinIntersection(
331
331
object_polygon, utils::toPolygon2d (lanelet::utils::to2D (polygon.basicPolygon ())));
332
332
}
333
333
334
- bool isOnEgoLane (const ObjectData & object)
334
+ bool isOnEgoLane (const ObjectData & object, const std::shared_ptr<RouteHandler> & route_handler )
335
335
{
336
336
const auto & object_pos = object.object .kinematics .initial_pose_with_covariance .pose .position ;
337
- return boost::geometry::within (
338
- lanelet::utils::to2D (lanelet::utils::conversion::toLaneletPoint (object_pos)).basicPoint (),
339
- object.overhang_lanelet .polygon2d ().basicPolygon ());
337
+ if (boost::geometry::within (
338
+ lanelet::utils::to2D (lanelet::utils::conversion::toLaneletPoint (object_pos)).basicPoint (),
339
+ object.overhang_lanelet .polygon2d ().basicPolygon ())) {
340
+ return true ;
341
+ }
342
+
343
+ // push previous lanelet
344
+ lanelet::ConstLanelets prev_lanelet;
345
+ if (route_handler->getPreviousLaneletsWithinRoute (object.overhang_lanelet , &prev_lanelet)) {
346
+ if (boost::geometry::within (
347
+ lanelet::utils::to2D (lanelet::utils::conversion::toLaneletPoint (object_pos)).basicPoint (),
348
+ prev_lanelet.front ().polygon2d ().basicPolygon ())) {
349
+ return true ;
350
+ }
351
+ }
352
+
353
+ // push next lanelet
354
+ lanelet::ConstLanelet next_lanelet;
355
+ if (route_handler->getNextLaneletWithinRoute (object.overhang_lanelet , &next_lanelet)) {
356
+ if (boost::geometry::within (
357
+ lanelet::utils::to2D (lanelet::utils::conversion::toLaneletPoint (object_pos)).basicPoint (),
358
+ next_lanelet.polygon2d ().basicPolygon ())) {
359
+ return true ;
360
+ }
361
+ }
362
+
363
+ return false ;
340
364
}
341
365
342
366
bool isParallelToEgoLane (const ObjectData & object, const double threshold)
@@ -754,7 +778,7 @@ bool isSatisfiedWithVehicleCondition(
754
778
const std::shared_ptr<AvoidanceParameters> & parameters)
755
779
{
756
780
object.behavior = getObjectBehavior (object, parameters);
757
- object.is_on_ego_lane = isOnEgoLane (object);
781
+ object.is_on_ego_lane = isOnEgoLane (object, planner_data-> route_handler );
758
782
759
783
if (isNeverAvoidanceTarget (object, data, planner_data, parameters)) {
760
784
return false ;
0 commit comments