Skip to content

Commit 16c0e83

Browse files
style(pre-commit): autofix
1 parent de78b43 commit 16c0e83

2 files changed

Lines changed: 13 additions & 12 deletions

File tree

planning/autoware_static_centerline_generator/README.md

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -110,11 +110,11 @@ By default, footprint colors are:
110110

111111
When embedding a fixed route from VMB, some routes may fail or produce incomplete centerlines. Common causes and remedies:
112112

113-
| Symptom / Error | Cause | What to check |
114-
|-----------------|--------|----------------|
115-
| **LaneletsNotConnected** | The lane IDs in the route are not topologically connected (next lanelet of one is not the following in the list). | In VMB, ensure the selected lane sequence is connected in the map (no skipped lanes, correct direction). |
116-
| **PathNotFound** | Optimization returned no trajectory (e.g. goal_method, very sharp curve, or degenerate lane). | Check `goal_method` and route shape; try a shorter or simpler segment. |
117-
| **InvalidRoute** | Request had an empty route. | Ensure the route selection in VMB sends at least one lane ID. |
118-
| **InvalidLanelet** | Start/goal lanelet has no valid centerline (e.g. centerline has fewer than 2 points). | Fix or regenerate the map so that lanelets have valid centerlines. |
119-
| **Some lanelets with no points** | Optimized path does not pass through every selected lanelet, or points fall outside polygon (e.g. sharp curves). | Check terminal for `PlanPath: lanelet id X has no assigned points`. Adjust route or map; sharp curves may need manual centerline. |
120-
| **Points outside all lanelets** | Smoothed trajectory lies slightly outside lane polygons (boundaries or optimization). | Terminal logs: `X trajectory point(s) were outside all lanelet polygons`. Points are still assigned to the nearest segment; if embedding looks wrong, simplify the route or check map geometry. |
113+
| Symptom / Error | Cause | What to check |
114+
| -------------------------------- | ----------------------------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
115+
| **LaneletsNotConnected** | The lane IDs in the route are not topologically connected (next lanelet of one is not the following in the list). | In VMB, ensure the selected lane sequence is connected in the map (no skipped lanes, correct direction). |
116+
| **PathNotFound** | Optimization returned no trajectory (e.g. goal_method, very sharp curve, or degenerate lane). | Check `goal_method` and route shape; try a shorter or simpler segment. |
117+
| **InvalidRoute** | Request had an empty route. | Ensure the route selection in VMB sends at least one lane ID. |
118+
| **InvalidLanelet** | Start/goal lanelet has no valid centerline (e.g. centerline has fewer than 2 points). | Fix or regenerate the map so that lanelets have valid centerlines. |
119+
| **Some lanelets with no points** | Optimized path does not pass through every selected lanelet, or points fall outside polygon (e.g. sharp curves). | Check terminal for `PlanPath: lanelet id X has no assigned points`. Adjust route or map; sharp curves may need manual centerline. |
120+
| **Points outside all lanelets** | Smoothed trajectory lies slightly outside lane polygons (boundaries or optimization). | Terminal logs: `X trajectory point(s) were outside all lanelet polygons`. Points are still assigned to the nearest segment; if embedding looks wrong, simplify the route or check map geometry. |

planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -158,8 +158,8 @@ std::vector<lanelet::Id> check_lanelet_connection(
158158

159159
void assign_centerline_points_to_lanelets(
160160
const std::vector<TrajectoryPoint> & optimized_traj_points,
161-
const lanelet::ConstLanelets & route_lanelets,
162-
PlanPath::Response::SharedPtr response, const rclcpp::Logger & logger)
161+
const lanelet::ConstLanelets & route_lanelets, PlanPath::Response::SharedPtr response,
162+
const rclcpp::Logger & logger)
163163
{
164164
std::vector<std::vector<geometry_msgs::msg::Point>> points_per_lanelet(route_lanelets.size());
165165
size_t current_lanelet_idx = 0;
@@ -168,8 +168,9 @@ void assign_centerline_points_to_lanelets(
168168
for (const auto & traj_point : optimized_traj_points) {
169169
const auto pt = convert_to_lanelet_point(traj_point.pose.position);
170170

171-
if (current_lanelet_idx < route_lanelets.size() &&
172-
lanelet::geometry::inside(route_lanelets.at(current_lanelet_idx), pt)) {
171+
if (
172+
current_lanelet_idx < route_lanelets.size() &&
173+
lanelet::geometry::inside(route_lanelets.at(current_lanelet_idx), pt)) {
173174
points_per_lanelet.at(current_lanelet_idx).push_back(traj_point.pose.position);
174175
continue;
175176
}

0 commit comments

Comments
 (0)