@@ -95,6 +95,7 @@ void Lanelet2MapVisualizationNode::onMapBin(
95
95
lanelet::ConstLanelets shoulder_lanelets = lanelet::utils::query::shoulderLanelets (all_lanelets);
96
96
lanelet::ConstLanelets crosswalk_lanelets =
97
97
lanelet::utils::query::crosswalkLanelets (all_lanelets);
98
+ lanelet::ConstLineStrings3d partitions = lanelet::utils::query::getAllPartitions (viz_lanelet_map);
98
99
lanelet::ConstLineStrings3d pedestrian_markings =
99
100
lanelet::utils::query::getAllPedestrianMarkings (viz_lanelet_map);
100
101
lanelet::ConstLanelets walkway_lanelets = lanelet::utils::query::walkwayLanelets (all_lanelets);
@@ -114,12 +115,13 @@ void Lanelet2MapVisualizationNode::onMapBin(
114
115
lanelet::ConstPolygons3d obstacle_polygons =
115
116
lanelet::utils::query::getAllObstaclePolygons (viz_lanelet_map);
116
117
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;
120
121
setColor (&cl_road, 0.27 , 0.27 , 0.27 , 0.999 );
121
122
setColor (&cl_shoulder, 0.15 , 0.15 , 0.15 , 0.999 );
122
123
setColor (&cl_cross, 0.27 , 0.3 , 0.27 , 0.5 );
124
+ setColor (&cl_partitions, 0.25 , 0.25 , 0.25 , 0.999 );
123
125
setColor (&cl_pedestrian_markings, 0.5 , 0.5 , 0.5 , 0.999 );
124
126
setColor (&cl_ll_borders, 0.5 , 0.5 , 0.5 , 0.999 );
125
127
setColor (&cl_shoulder_borders, 0.2 , 0.2 , 0.2 , 0.999 );
@@ -137,6 +139,9 @@ void Lanelet2MapVisualizationNode::onMapBin(
137
139
insertMarkerArray (
138
140
&map_marker_array,
139
141
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 ));
140
145
insertMarkerArray (
141
146
&map_marker_array,
142
147
lanelet::visualization::laneletDirectionAsMarkerArray (shoulder_lanelets, " shoulder_" ));
0 commit comments