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

feat(detected_object_validation): add BOUNDING_BOX interface to lanelet filter #3957

Merged
merged 3 commits into from
Jun 20, 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 @@ -63,6 +63,8 @@ class ObjectLaneletFilterNode : public rclcpp::Node
lanelet::ConstLanelets getIntersectedLanelets(
const LinearRing2d &, const lanelet::ConstLanelets &);
bool isPolygonOverlapLanelets(const Polygon2d &, const lanelet::ConstLanelets &);
geometry_msgs::msg::Polygon setFootprint(
const autoware_auto_perception_msgs::msg::DetectedObject &);
};

} // namespace object_lanelet_filter
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

## Purpose

The `object_lanelet_filter` is a node that filters detected object by using vector map.
The `object_lanelet_filter` is a node that filters detected object by using vector map.
The objects only inside of the vector map will be published.

## Inner-workings / Algorithms
Expand Down Expand Up @@ -39,7 +39,7 @@ The objects only inside of the vector map will be published.

## Assumptions / Known limits

Filtering is performed based on the shape polygon of the object.
The lanelet filter is performed based on the shape polygon and bounding box of the objects.

## (Optional) Error detection and handling

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ void ObjectLaneletFilterNode::objectCallback(

int index = 0;
for (const auto & object : transformed_objects.objects) {
const auto & footprint = object.shape.footprint;
const auto footprint = setFootprint(object);
const auto & label = object.classification.front().label;
if (filter_target_.isTarget(label)) {
Polygon2d polygon;
Expand All @@ -110,13 +110,39 @@ void ObjectLaneletFilterNode::objectCallback(
object_pub_->publish(output_object_msg);
}

geometry_msgs::msg::Polygon ObjectLaneletFilterNode::setFootprint(
const autoware_auto_perception_msgs::msg::DetectedObject & detected_object)
{
geometry_msgs::msg::Polygon footprint;
if (detected_object.shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) {
const auto object_size = detected_object.shape.dimensions;
const double x_front = object_size.x / 2.0;
const double x_rear = -object_size.x / 2.0;
const double y_left = object_size.y / 2.0;
const double y_right = -object_size.y / 2.0;

footprint.points.push_back(
geometry_msgs::build<geometry_msgs::msg::Point32>().x(x_front).y(y_left).z(0.0));
footprint.points.push_back(
geometry_msgs::build<geometry_msgs::msg::Point32>().x(x_front).y(y_right).z(0.0));
footprint.points.push_back(
geometry_msgs::build<geometry_msgs::msg::Point32>().x(x_rear).y(y_right).z(0.0));
footprint.points.push_back(
geometry_msgs::build<geometry_msgs::msg::Point32>().x(x_rear).y(y_left).z(0.0));
} else {
footprint = detected_object.shape.footprint;
}
return footprint;
}

LinearRing2d ObjectLaneletFilterNode::getConvexHull(
const autoware_auto_perception_msgs::msg::DetectedObjects & detected_objects)
{
MultiPoint2d candidate_points;
for (const auto & object : detected_objects.objects) {
const auto & pos = object.kinematics.pose_with_covariance.pose.position;
for (const auto & p : object.shape.footprint.points) {
const auto footprint = setFootprint(object);
for (const auto & p : footprint.points) {
candidate_points.emplace_back(p.x + pos.x, p.y + pos.y);
}
}
Expand Down