Skip to content

Commit d638b95

Browse files
authored
feat(lanelet2_extension,map_loader): add guard_rail wall fence as lanelet tag (#478)
* feat(lanelet2_extension): add guard_rails fence wall as lanelet tag Signed-off-by: tanaka3 <ttatcoder@outlook.jp> * feat(map_loader): add visualization for partion lanelet Signed-off-by: tanaka3 <ttatcoder@outlook.jp>
1 parent 52cdb76 commit d638b95

File tree

3 files changed

+25
-3
lines changed

3 files changed

+25
-3
lines changed

map/lanelet2_extension/include/lanelet2_extension/utility/query.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -123,6 +123,9 @@ lanelet::ConstPolygons3d getAllObstaclePolygons(
123123
// query all parking lots in lanelet2 map
124124
lanelet::ConstPolygons3d getAllParkingLots(const lanelet::LaneletMapConstPtr & lanelet_map_ptr);
125125

126+
// query all partitions in lanelet2 map
127+
lanelet::ConstLineStrings3d getAllPartitions(const lanelet::LaneletMapConstPtr & lanelet_map_ptr);
128+
126129
// query all pedestrian markings in lanelet2 map
127130
lanelet::ConstLineStrings3d getAllPedestrianMarkings(
128131
const lanelet::LaneletMapConstPtr & lanelet_map_ptr);

map/lanelet2_extension/lib/query.cpp

+14
Original file line numberDiff line numberDiff line change
@@ -241,6 +241,20 @@ lanelet::ConstPolygons3d query::getAllParkingLots(
241241
return parking_lots;
242242
}
243243

244+
lanelet::ConstLineStrings3d query::getAllPartitions(
245+
const lanelet::LaneletMapConstPtr & lanelet_map_ptr)
246+
{
247+
lanelet::ConstLineStrings3d partitions;
248+
for (const auto & ls : lanelet_map_ptr->lineStringLayer) {
249+
const std::string type = ls.attributeOr(lanelet::AttributeName::Type, "none");
250+
if (
251+
type.compare("guard_rail") == 0 || type.compare("fence") == 0 || type.compare("wall") == 0) {
252+
partitions.push_back(ls);
253+
}
254+
}
255+
return partitions;
256+
}
257+
244258
lanelet::ConstLineStrings3d query::getAllPedestrianMarkings(
245259
const lanelet::LaneletMapConstPtr & lanelet_map_ptr)
246260
{

map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp

+8-3
Original file line numberDiff line numberDiff line change
@@ -95,6 +95,7 @@ void Lanelet2MapVisualizationNode::onMapBin(
9595
lanelet::ConstLanelets shoulder_lanelets = lanelet::utils::query::shoulderLanelets(all_lanelets);
9696
lanelet::ConstLanelets crosswalk_lanelets =
9797
lanelet::utils::query::crosswalkLanelets(all_lanelets);
98+
lanelet::ConstLineStrings3d partitions = lanelet::utils::query::getAllPartitions(viz_lanelet_map);
9899
lanelet::ConstLineStrings3d pedestrian_markings =
99100
lanelet::utils::query::getAllPedestrianMarkings(viz_lanelet_map);
100101
lanelet::ConstLanelets walkway_lanelets = lanelet::utils::query::walkwayLanelets(all_lanelets);
@@ -114,12 +115,13 @@ void Lanelet2MapVisualizationNode::onMapBin(
114115
lanelet::ConstPolygons3d obstacle_polygons =
115116
lanelet::utils::query::getAllObstaclePolygons(viz_lanelet_map);
116117

117-
std_msgs::msg::ColorRGBA cl_road, cl_shoulder, cl_cross, cl_pedestrian_markings, cl_ll_borders,
118-
cl_shoulder_borders, cl_stoplines, cl_trafficlights, cl_detection_areas, cl_parking_lots,
119-
cl_parking_spaces, cl_lanelet_id, cl_obstacle_polygons, cl_no_stopping_areas;
118+
std_msgs::msg::ColorRGBA cl_road, cl_shoulder, cl_cross, cl_partitions, cl_pedestrian_markings,
119+
cl_ll_borders, cl_shoulder_borders, cl_stoplines, cl_trafficlights, cl_detection_areas,
120+
cl_parking_lots, cl_parking_spaces, cl_lanelet_id, cl_obstacle_polygons, cl_no_stopping_areas;
120121
setColor(&cl_road, 0.27, 0.27, 0.27, 0.999);
121122
setColor(&cl_shoulder, 0.15, 0.15, 0.15, 0.999);
122123
setColor(&cl_cross, 0.27, 0.3, 0.27, 0.5);
124+
setColor(&cl_partitions, 0.25, 0.25, 0.25, 0.999);
123125
setColor(&cl_pedestrian_markings, 0.5, 0.5, 0.5, 0.999);
124126
setColor(&cl_ll_borders, 0.5, 0.5, 0.5, 0.999);
125127
setColor(&cl_shoulder_borders, 0.2, 0.2, 0.2, 0.999);
@@ -137,6 +139,9 @@ void Lanelet2MapVisualizationNode::onMapBin(
137139
insertMarkerArray(
138140
&map_marker_array,
139141
lanelet::visualization::lineStringsAsMarkerArray(stop_lines, "stop_lines", cl_stoplines, 0.5));
142+
insertMarkerArray(
143+
&map_marker_array,
144+
lanelet::visualization::lineStringsAsMarkerArray(partitions, "partitions", cl_partitions, 0.1));
140145
insertMarkerArray(
141146
&map_marker_array,
142147
lanelet::visualization::laneletDirectionAsMarkerArray(shoulder_lanelets, "shoulder_"));

0 commit comments

Comments
 (0)