File tree 1 file changed +10
-0
lines changed
planning/behavior_path_avoidance_module/src
1 file changed +10
-0
lines changed Original file line number Diff line number Diff line change @@ -618,6 +618,10 @@ bool isForceAvoidanceTarget(
618
618
const std::shared_ptr<const PlannerData> & planner_data,
619
619
const std::shared_ptr<AvoidanceParameters> & parameters)
620
620
{
621
+ using boost::geometry::within;
622
+ using lanelet::utils::to2D;
623
+ using lanelet::utils::conversion::toLaneletPoint;
624
+
621
625
if (!parameters->enable_force_avoidance_for_stopped_vehicle ) {
622
626
return false ;
623
627
}
@@ -653,6 +657,12 @@ bool isForceAvoidanceTarget(
653
657
}
654
658
655
659
const auto & ego_pose = planner_data->self_odometry ->pose .pose ;
660
+ const auto on_ego_driving_lane = within (
661
+ to2D (toLaneletPoint (object_pose.position )).basicPoint (),
662
+ object.overhang_lanelet .polygon2d ().basicPolygon ());
663
+ if (!on_ego_driving_lane) {
664
+ return true ;
665
+ }
656
666
657
667
// force avoidance for stopped vehicle
658
668
bool not_parked_object = true ;
You can’t perform that action at this time.
0 commit comments