Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(detected_object_validation): consider shoulder lanelet in object lanelet filter #5324

Merged
merged 2 commits into from
Oct 18, 2023
Merged
Show file tree
Hide file tree
Changes from 1 commit
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 @@ -51,6 +51,7 @@ class ObjectLaneletFilterNode : public rclcpp::Node

lanelet::LaneletMapPtr lanelet_map_ptr_;
lanelet::ConstLanelets road_lanelets_;
lanelet::ConstLanelets shoulder_lanelets_;
std::string lanelet_frame_id_;

tf2_ros::Buffer tf_buffer_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,7 @@ void ObjectLaneletFilterNode::mapCallback(
lanelet::utils::conversion::fromBinMsg(*map_msg, lanelet_map_ptr_);
const lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_ptr_);
road_lanelets_ = lanelet::utils::query::roadLanelets(all_lanelets);
shoulder_lanelets_ = lanelet::utils::query::shoulderLanelets(all_lanelets);
}

void ObjectLaneletFilterNode::objectCallback(
Expand All @@ -87,7 +88,8 @@ void ObjectLaneletFilterNode::objectCallback(
// calculate convex hull
const auto convex_hull = getConvexHull(transformed_objects);
// get intersected lanelets
lanelet::ConstLanelets intersected_lanelets = getIntersectedLanelets(convex_hull, road_lanelets_);
lanelet::ConstLanelets intersected_road_lanelets = getIntersectedLanelets(convex_hull, road_lanelets_);
lanelet::ConstLanelets intersected_shoulder_lanelets = getIntersectedLanelets(convex_hull, shoulder_lanelets_);

int index = 0;
for (const auto & object : transformed_objects.objects) {
Expand All @@ -101,7 +103,10 @@ void ObjectLaneletFilterNode::objectCallback(
polygon.outer().emplace_back(point_transformed.x, point_transformed.y);
}
polygon.outer().push_back(polygon.outer().front());
if (isPolygonOverlapLanelets(polygon, intersected_lanelets)) {
if (isPolygonOverlapLanelets(polygon, intersected_road_lanelets)) {
output_object_msg.objects.emplace_back(input_msg->objects.at(index));
}
else if (isPolygonOverlapLanelets(polygon, intersected_shoulder_lanelets)) {
output_object_msg.objects.emplace_back(input_msg->objects.at(index));
}
} else {
Expand Down