Skip to content

Commit a606563

Browse files
authored
Merge branch 'beta/v0.11.2' into fix/ndt_scan_matcher/delete_diagnostics_thread
2 parents e7bc713 + f74b33d commit a606563

File tree

2 files changed

+20
-1
lines changed

2 files changed

+20
-1
lines changed

map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp

+7-1
Original file line numberDiff line numberDiff line change
@@ -127,13 +127,14 @@ void Lanelet2MapVisualizationNode::onMapBin(
127127
lanelet::utils::query::getAllPolygonsByType(viz_lanelet_map, "hatched_road_markings");
128128
std::vector<lanelet::NoParkingAreaConstPtr> no_parking_reg_elems =
129129
lanelet::utils::query::noParkingAreas(all_lanelets);
130+
lanelet::ConstLineStrings3d curbstones = lanelet::utils::query::curbstones(viz_lanelet_map);
130131

131132
std_msgs::msg::ColorRGBA cl_road, cl_shoulder, cl_cross, cl_partitions, cl_pedestrian_markings,
132133
cl_ll_borders, cl_shoulder_borders, cl_stoplines, cl_trafficlights, cl_detection_areas,
133134
cl_speed_bumps, cl_crosswalks, cl_parking_lots, cl_parking_spaces, cl_lanelet_id,
134135
cl_obstacle_polygons, cl_no_stopping_areas, cl_no_obstacle_segmentation_area,
135136
cl_no_obstacle_segmentation_area_for_run_out, cl_hatched_road_markings_area,
136-
cl_hatched_road_markings_line, cl_no_parking_areas;
137+
cl_hatched_road_markings_line, cl_no_parking_areas, cl_curbstones;
137138
setColor(&cl_road, 0.27, 0.27, 0.27, 0.999);
138139
setColor(&cl_shoulder, 0.15, 0.15, 0.15, 0.999);
139140
setColor(&cl_cross, 0.27, 0.3, 0.27, 0.5);
@@ -156,6 +157,7 @@ void Lanelet2MapVisualizationNode::onMapBin(
156157
setColor(&cl_hatched_road_markings_area, 0.3, 0.3, 0.3, 0.5);
157158
setColor(&cl_hatched_road_markings_line, 0.5, 0.5, 0.5, 0.999);
158159
setColor(&cl_no_parking_areas, 0.42, 0.42, 0.42, 0.5);
160+
setColor(&cl_curbstones, 0.1, 0.1, 0.2, 0.999);
159161

160162
visualization_msgs::msg::MarkerArray map_marker_array;
161163

@@ -242,6 +244,10 @@ void Lanelet2MapVisualizationNode::onMapBin(
242244
&map_marker_array,
243245
lanelet::visualization::noParkingAreasAsMarkerArray(no_parking_reg_elems, cl_no_parking_areas));
244246

247+
insertMarkerArray(
248+
&map_marker_array,
249+
lanelet::visualization::lineStringsAsMarkerArray(curbstones, "curbstone", cl_curbstones, 0.2));
250+
245251
pub_marker_->publish(map_marker_array);
246252
}
247253

planning/behavior_path_planner/src/utils/utils.cpp

+13
Original file line numberDiff line numberDiff line change
@@ -1586,6 +1586,8 @@ std::vector<lanelet::ConstPoint3d> getBoundWithHatchedRoadMarkings(
15861586
} else {
15871587
if (!polygon) {
15881588
will_close_polygon = true;
1589+
} else if (polygon.value().id() != current_polygon.value().id()) {
1590+
will_close_polygon = true;
15891591
} else {
15901592
current_polygon_border_indices.push_back(
15911593
get_corresponding_polygon_index(*current_polygon, bound_point.id()));
@@ -1620,6 +1622,17 @@ std::vector<lanelet::ConstPoint3d> getBoundWithHatchedRoadMarkings(
16201622
(*current_polygon)[mod(target_poly_idx, current_polygon_points_num)]);
16211623
}
16221624
}
1625+
1626+
if (polygon.has_value() && current_polygon.has_value()) {
1627+
if (polygon.value().id() != current_polygon.value().id()) {
1628+
current_polygon = polygon;
1629+
current_polygon_border_indices.clear();
1630+
current_polygon_border_indices.push_back(
1631+
get_corresponding_polygon_index(current_polygon.value(), bound_point.id()));
1632+
continue;
1633+
}
1634+
}
1635+
16231636
current_polygon = std::nullopt;
16241637
current_polygon_border_indices.clear();
16251638
}

0 commit comments

Comments
 (0)