Skip to content

Commit d56287d

Browse files
committed
fix(lanelet_filter): add crosswalk lanelet filter
Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>
1 parent f0f5736 commit d56287d

File tree

1 file changed

+3
-2
lines changed

1 file changed

+3
-2
lines changed

perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -257,12 +257,13 @@ std::vector<BoxAndLanelet> ObjectLaneletFilterNode::getIntersectedLanelets(
257257

258258
const lanelet::Lanelets candidate_lanelets = lanelet_map_ptr_->laneletLayer.search(bbox2d);
259259
for (const auto & lanelet : candidate_lanelets) {
260-
// only check the road lanelets and road shoulder lanelets
260+
// check the road lanelets, road shoulder lanelets and crosswalks lanelets
261261
if (
262262
lanelet.hasAttribute(lanelet::AttributeName::Subtype) &&
263263
(lanelet.attribute(lanelet::AttributeName::Subtype).value() ==
264264
lanelet::AttributeValueString::Road ||
265-
lanelet.attribute(lanelet::AttributeName::Subtype).value() == "road_shoulder")) {
265+
lanelet.attribute(lanelet::AttributeName::Subtype).value() == "road_shoulder" ||
266+
lanelet.attribute(lanelet::AttributeName::Subtype).value() == "crosswalk")) {
266267
if (bg::intersects(convex_hull, lanelet.polygon2d().basicPolygon())) {
267268
// create bbox using boost for making the R-tree in later phase
268269
lanelet::BoundingBox2d lanelet_bbox = lanelet::geometry::boundingBox2d(lanelet);

0 commit comments

Comments
 (0)