Skip to content

Commit 06b66c1

Browse files
pre-commit-ci[bot]kosuke55
authored andcommitted
style(pre-commit): autofix
1 parent e4094d5 commit 06b66c1

File tree

1 file changed

+3
-2
lines changed

1 file changed

+3
-2
lines changed

planning/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -254,7 +254,7 @@ bool NoStoppingAreaModule::checkStopLinesInNoStoppingArea(
254254

255255
// if the detected stop point is near goal, it's ignored.
256256
const double close_to_goal_distance = 1.0;
257-
257+
258258
// stuck points by stop line
259259
for (size_t i = 0; i < path.points.size() - 1; ++i) {
260260
const auto p0 = path.points.at(i).point.pose.position;
@@ -265,7 +265,8 @@ bool NoStoppingAreaModule::checkStopLinesInNoStoppingArea(
265265
continue;
266266
}
267267
// judge if stop point p0 is near goal, by its distance to the path end.
268-
const double dist_to_path_end = motion_utils::calcSignedArcLength(path.points, i, path.points.size() - 1);
268+
const double dist_to_path_end =
269+
motion_utils::calcSignedArcLength(path.points, i, path.points.size() - 1);
269270
if (dist_to_path_end < close_to_goal_distance) {
270271
// exit with false, cause position is near goal.
271272
return false;

0 commit comments

Comments
 (0)