Skip to content

Commit 8461b38

Browse files
kaigohiraopre-commit-ci[bot]shmpwkkosuke55
committed
fix(no_stopping_area): skip drawing a stop line in the case where the detected stop lines are goals (autowarefoundation#7280)
* Revert "fix(no_stopping_area): fix stopping in front of a no stopping area in parking on the shoulder (autowarefoundation#6517)" This reverts commit 144b9c7. * if the stop point is near goal(distance < 1m), no stopping area module does not insert stop line * style(pre-commit): autofix * Update planning/behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp --------- Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Shumpei Wakabayashi <42209144+shmpwk@users.noreply.github.com> Co-authored-by: kosuke55 <kosuke.tnp@gmail.com>
1 parent edb6232 commit 8461b38

File tree

1 file changed

+15
-6
lines changed

1 file changed

+15
-6
lines changed

planning/behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp

+15-6
Original file line numberDiff line numberDiff line change
@@ -257,6 +257,10 @@ bool NoStoppingAreaModule::checkStopLinesInNoStoppingArea(
257257
const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const Polygon2d & poly)
258258
{
259259
const double stop_vel = std::numeric_limits<float>::min();
260+
261+
// if the detected stop point is near goal, it's ignored.
262+
static constexpr double close_to_goal_distance = 1.0;
263+
260264
// stuck points by stop line
261265
for (size_t i = 0; i < path.points.size() - 1; ++i) {
262266
const auto p0 = path.points.at(i).point.pose.position;
@@ -266,6 +270,14 @@ bool NoStoppingAreaModule::checkStopLinesInNoStoppingArea(
266270
if (v0 > stop_vel && v1 > stop_vel) {
267271
continue;
268272
}
273+
// judge if stop point p0 is near goal, by its distance to the path end.
274+
const double dist_to_path_end =
275+
motion_utils::calcSignedArcLength(path.points, i, path.points.size() - 1);
276+
if (dist_to_path_end < close_to_goal_distance) {
277+
// exit with false, cause position is near goal.
278+
return false;
279+
}
280+
269281
const LineString2d line{{p0.x, p0.y}, {p1.x, p1.y}};
270282
std::vector<Point2d> collision_points;
271283
bg::intersection(poly, line, collision_points);
@@ -324,7 +336,9 @@ Polygon2d NoStoppingAreaModule::generateEgoNoStoppingAreaLanePolygon(
324336
}
325337
++ego_area_start_idx;
326338
}
327-
339+
if (ego_area_start_idx > num_ignore_nearest) {
340+
ego_area_start_idx--;
341+
}
328342
if (!is_in_area) {
329343
return ego_area;
330344
}
@@ -336,11 +350,6 @@ Polygon2d NoStoppingAreaModule::generateEgoNoStoppingAreaLanePolygon(
336350
const auto & p = pp.at(i).point.pose.position;
337351
if (!bg::within(Point2d{p.x, p.y}, lanelet::utils::to2D(no_stopping_area).basicPolygon())) {
338352
dist_from_area_sum += tier4_autoware_utils::calcDistance2d(pp.at(i), pp.at(i - 1));
339-
340-
// do not take extra distance and exit as soon as p is outside no stopping area
341-
// just a temporary fix
342-
ego_area_end_idx = i - 1;
343-
break;
344353
}
345354
if (dist_from_start_sum > extra_dist || dist_from_area_sum > margin) {
346355
break;

0 commit comments

Comments
 (0)