Skip to content
This repository was archived by the owner on Jul 1, 2024. It is now read-only.

Commit 13beab1

Browse files
Ahmed Ebrahimahmeddesokyebrahim
Ahmed Ebrahim
authored andcommitted
fix(log-messages): proposing solution to warn messages "lineStringToPolygon: linestring x must have more than different 3 points! (size is 2). Failed to convert to polygon." and "pedestrian marking x failed conversion."
Signed-off-by: AhmedEbrahim <ahmed.a.d.ebrahim@gmail.com>
1 parent 829464c commit 13beab1

File tree

4 files changed

+72
-19
lines changed

4 files changed

+72
-19
lines changed

tmp/lanelet2_extension/include/lanelet2_extension/utility/query.hpp

+6-2
Original file line numberDiff line numberDiff line change
@@ -149,8 +149,12 @@ lanelet::ConstLineStrings3d getAllPartitions(const lanelet::LaneletMapConstPtr &
149149
// query all fences in lanelet2 map
150150
lanelet::ConstLineStrings3d getAllFences(const lanelet::LaneletMapConstPtr & lanelet_map_ptr);
151151

152-
// query all pedestrian markings in lanelet2 map
153-
lanelet::ConstLineStrings3d getAllPedestrianMarkings(
152+
// query all pedestrian polygon markings in lanelet2 map
153+
lanelet::ConstLineStrings3d getAllPedestrianPolygonMarkings(
154+
const lanelet::LaneletMapConstPtr & lanelet_map_ptr);
155+
156+
// query all pedestrian line markings in lanelet2 map
157+
lanelet::ConstLineStrings3d getAllPedestrianLineMarkings(
154158
const lanelet::LaneletMapConstPtr & lanelet_map_ptr);
155159

156160
// query all parking spaces in lanelet2 map

tmp/lanelet2_extension/include/lanelet2_extension/visualization/visualization.hpp

+12-4
Original file line numberDiff line numberDiff line change
@@ -275,12 +275,20 @@ visualization_msgs::msg::MarkerArray crosswalkAreasAsMarkerArray(
275275
const rclcpp::Duration & duration = rclcpp::Duration(0, 0));
276276

277277
/**
278-
* [pedestrianMarkingsAsMarkerArray creates marker array to visualize pedestrian markings]
279-
* @param pedestrian_markings [pedestrian marking polygon]
278+
* [pedestrianPolygonMarkingsAsMarkerArray creates marker array to visualize pedestrian polygon markings]
279+
* @param pedestrian_polygon_markings [pedestrian marking polygon]
280280
* @param c [color of the marker]
281281
*/
282-
visualization_msgs::msg::MarkerArray pedestrianMarkingsAsMarkerArray(
283-
const lanelet::ConstLineStrings3d & pedestrian_markings, const std_msgs::msg::ColorRGBA & c);
282+
visualization_msgs::msg::MarkerArray pedestrianPolygonMarkingsAsMarkerArray(
283+
const lanelet::ConstLineStrings3d & pedestrian_polygon_markings, const std_msgs::msg::ColorRGBA & c);
284+
285+
/**
286+
* [pedestrianLineMarkingsAsMarkerArray creates marker array to visualize pedestrian line markings]
287+
* @param pedestrian_line_markings [pedestrian marking line]
288+
* @param c [color of the marker]
289+
*/
290+
visualization_msgs::msg::MarkerArray pedestrianLineMarkingsAsMarkerArray(
291+
const lanelet::ConstLineStrings3d & pedestrian_line_markings, const std_msgs::msg::ColorRGBA & c);
284292

285293
/**
286294
* [parkingLotsAsMarkerArray creates marker array to visualize parking lots]

tmp/lanelet2_extension/lib/query.cpp

+18-5
Original file line numberDiff line numberDiff line change
@@ -381,17 +381,30 @@ lanelet::ConstLineStrings3d query::getAllFences(const lanelet::LaneletMapConstPt
381381
return fences;
382382
}
383383

384-
lanelet::ConstLineStrings3d query::getAllPedestrianMarkings(
384+
lanelet::ConstLineStrings3d query::getAllPedestrianPolygonMarkings(
385385
const lanelet::LaneletMapConstPtr & lanelet_map_ptr)
386386
{
387-
lanelet::ConstLineStrings3d pedestrian_markings;
387+
lanelet::ConstLineStrings3d pedestrian_polygon_markings;
388388
for (const auto & ls : lanelet_map_ptr->lineStringLayer) {
389389
const std::string type = ls.attributeOr(lanelet::AttributeName::Type, "none");
390-
if (type == "pedestrian_marking") {
391-
pedestrian_markings.push_back(ls);
390+
if ((type == "pedestrian_marking") && (ls.size() >= 3)) {
391+
pedestrian_polygon_markings.push_back(ls);
392392
}
393393
}
394-
return pedestrian_markings;
394+
return pedestrian_polygon_markings;
395+
}
396+
397+
lanelet::ConstLineStrings3d query::getAllPedestrianLineMarkings(
398+
const lanelet::LaneletMapConstPtr & lanelet_map_ptr)
399+
{
400+
lanelet::ConstLineStrings3d pedestrian_line_markings;
401+
for (const auto & ls : lanelet_map_ptr->lineStringLayer) {
402+
const std::string type = ls.attributeOr(lanelet::AttributeName::Type, "none");
403+
if ((type == "pedestrian_marking") && (ls.size() < 3)) {
404+
pedestrian_line_markings.push_back(ls);
405+
}
406+
}
407+
return pedestrian_line_markings;
395408
}
396409

397410
lanelet::ConstLineStrings3d query::getAllParkingSpaces(

tmp/lanelet2_extension/lib/visualization.cpp

+36-8
Original file line numberDiff line numberDiff line change
@@ -974,29 +974,57 @@ visualization_msgs::msg::MarkerArray visualization::crosswalkAreasAsMarkerArray(
974974
return marker_array;
975975
}
976976

977-
visualization_msgs::msg::MarkerArray visualization::pedestrianMarkingsAsMarkerArray(
978-
const lanelet::ConstLineStrings3d & pedestrian_markings, const std_msgs::msg::ColorRGBA & c)
977+
visualization_msgs::msg::MarkerArray visualization::pedestrianPolygonMarkingsAsMarkerArray(
978+
const lanelet::ConstLineStrings3d & pedestrian_polygon_markings, const std_msgs::msg::ColorRGBA & c)
979979
{
980980
visualization_msgs::msg::MarkerArray marker_array;
981-
if (pedestrian_markings.empty()) {
981+
if (pedestrian_polygon_markings.empty()) {
982982
return marker_array;
983983
}
984984

985-
visualization_msgs::msg::Marker marker = createPolygonMarker("pedestrian_marking", c);
986-
for (const auto & linestring : pedestrian_markings) {
985+
visualization_msgs::msg::Marker polygon_marker = createPolygonMarker("pedestrian_polygon_marking", c);
986+
for (const auto & linestring : pedestrian_polygon_markings) {
987987
lanelet::ConstPolygon3d polygon;
988988
if (utils::lineStringToPolygon(linestring, &polygon)) {
989-
pushPolygonMarker(&marker, polygon, c);
989+
pushPolygonMarker(&polygon_marker, polygon, c);
990990
} else {
991991
RCLCPP_WARN_STREAM(
992992
rclcpp::get_logger("lanelet2_extension.visualization"),
993993
"pedestrian marking " << linestring.id() << " failed conversion.");
994994
}
995995
}
996996

997-
if (!marker.points.empty()) {
998-
marker_array.markers.push_back(marker);
997+
if (!polygon_marker.points.empty()) {
998+
marker_array.markers.push_back(polygon_marker);
999+
}
1000+
1001+
return marker_array;
1002+
}
1003+
1004+
visualization_msgs::msg::MarkerArray visualization::pedestrianLineMarkingsAsMarkerArray(
1005+
const lanelet::ConstLineStrings3d & pedestrian_line_markings, const std_msgs::msg::ColorRGBA & c)
1006+
{
1007+
visualization_msgs::msg::MarkerArray marker_array;
1008+
if (pedestrian_line_markings.empty()) {
1009+
return marker_array;
9991010
}
1011+
1012+
const float lss = 0.1; // line string size
1013+
visualization_msgs::msg::Marker line_marker;
1014+
visualization::initLineStringMarker(
1015+
&line_marker, "map", "pedestrian_line_marking", c);
1016+
1017+
for (const auto & linestring : pedestrian_line_markings) {
1018+
if ((linestring.size() < 3) && (linestring.front().id() != linestring.back().id())){
1019+
pushLineStringMarker(&line_marker, linestring, c, lss);
1020+
1021+
}
1022+
}
1023+
1024+
if (!line_marker.points.empty()) {
1025+
marker_array.markers.push_back(line_marker);
1026+
}
1027+
10001028
return marker_array;
10011029
}
10021030

0 commit comments

Comments
 (0)