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

feat(lanelet2_extensions): add query curbstones from vector map #206

Merged
merged 3 commits into from
Sep 13, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -129,6 +129,9 @@ std::vector<lanelet::SpeedBumpConstPtr> speedBumps(const lanelet::ConstLanelets
*/
std::vector<lanelet::CrosswalkConstPtr> crosswalks(const lanelet::ConstLanelets & lanelets);

// query all curbstones in lanelet2 map
lanelet::ConstLineStrings3d curbstones(const lanelet::LaneletMapConstPtr & lanelet_map_ptr);

// query all polygons that has given type in lanelet2 map
lanelet::ConstPolygons3d getAllPolygonsByType(
const lanelet::LaneletMapConstPtr & lanelet_map_ptr, const std::string & polygon_type);
Expand Down
12 changes: 12 additions & 0 deletions tmp/lanelet2_extension/lib/query.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -305,6 +305,18 @@ std::vector<lanelet::CrosswalkConstPtr> query::crosswalks(const lanelet::ConstLa
return cw_reg_elems;
}

lanelet::ConstLineStrings3d query::curbstones(const lanelet::LaneletMapConstPtr & lanelet_map_ptr)
{
lanelet::ConstLineStrings3d curbstones;
for (const auto & ls : lanelet_map_ptr->lineStringLayer) {
const std::string type = ls.attributeOr(lanelet::AttributeName::Type, "none");
if (type == "curbstone") {
curbstones.push_back(ls);
}
}
return curbstones;
}

lanelet::ConstPolygons3d query::getAllPolygonsByType(
const lanelet::LaneletMapConstPtr & lanelet_map_ptr, const std::string & polygon_type)
{
Expand Down