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(autoware_detected_object_validation): add height filter in lanelet filtering #10003

Merged
merged 7 commits into from
Jan 22, 2025
Merged
Show file tree
Hide file tree
Changes from 6 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 @@ -83,6 +83,10 @@ if(BUILD_TESTING)
test/test_utils.cpp
test/object_position_filter/test_object_position_filter.cpp
)
ament_auto_add_gtest(object_lanelet_filter_tests
test/test_utils.cpp
test/lanelet_filter/test_lanelet_filter.cpp
)
endif()

ament_auto_package(INSTALL_TO_SHARE
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,3 +21,6 @@
object_speed_threshold: 3.0 # [m/s]
debug: false
lanelet_extra_margin: 0.0
use_height_threshold: false
max_height_threshold: 10.0 # [m] from the base_link height in map frame
min_height_threshold: -1.0 # [m] from the base_link height in map frame
Original file line number Diff line number Diff line change
Expand Up @@ -24,10 +24,19 @@ The objects only inside of the vector map will be published.

## Parameters

| Name | Type | Description |
| ---------------------- | -------- | ------------------------------------------------------------------------------------ |
| `debug` | `bool` | if true, publish debug markers |
| `lanelet_extra_margin` | `double` | `if > 0` lanelet polygons are expanded by extra margin, `if <= 0` margin is disabled |
Description of the `filter_settings` in the parameters of the `object_lanelet_filter` node.

| Name | Type | Description |
| ------------------------------------------------- | -------- | ------------------------------------------------------------------------------------------------------------------------------------- |
| `debug` | `bool` | If `true`, publishes additional debug information, including visualization markers on the `~/debug/marker` topic for tools like RViz. |
| `lanelet_extra_margin` | `double` | If `> 0`, expands the lanelet polygons used for overlap checks by this margin (in meters). If `<= 0`, polygon expansion is disabled. |
| `polygon_overlap_filter.enabled` | `bool` | If `true`, enables filtering of objects based on their overlap with lanelet polygons. |
| `lanelet_direction_filter.enabled` | `bool` | If `true`, enables filtering of objects based on their velocity direction relative to the lanelet. |
| `lanelet_direction_filter.velocity_yaw_threshold` | `double` | The yaw angle difference threshold (in radians) between the object’s velocity vector and the lanelet direction. |
| `lanelet_direction_filter.object_speed_threshold` | `double` | The minimum speed (in m/s) of an object required for the direction filter to be applied. |
| `use_height_threshold` | `bool` | If `true`, enables filtering of objects based on their height relative to the base_link frame. |
| `max_height_threshold` | `double` | The maximum allowable height (in meters) of an object relative to the base_link in the map frame. |
| `min_height_threshold` | `double` | The minimum allowable height (in meters) of an object relative to the base_link in the map frame. |

### Core Parameters

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -95,9 +95,42 @@
}
},
"required": ["enabled", "velocity_yaw_threshold", "object_speed_threshold"]
},
"debug": {
"type": "boolean",
"default": false,
"description": "If true, debug information is enabled."
},
"lanelet_extra_margin": {
"type": "number",
"default": 0.0,
"description": "Extra margin added to the lanelet boundaries."
},
"use_height_threshold": {
"type": "boolean",
"default": false,
"description": "If true, height thresholds are used to filter objects."
},
"max_height_threshold": {
"type": "number",
"default": 10.0,
"description": "Maximum height threshold for filtering objects (in meters)."
},
"min_height_threshold": {
"type": "number",
"default": -1.0,
"description": "Minimum height threshold for filtering objects (in meters)."
}
Comment on lines +114 to 123
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@YoshiRi
Please add description which frame_id is based for these parameters?
I think it should be map/lanelet_frame_id_ as there is a transformation to lanelet_frame_id_ at

autoware_perception_msgs::msg::DetectedObjects transformed_objects;
if (!autoware::object_recognition_utils::transformObjects(
*input_msg, lanelet_frame_id_, tf_buffer_, transformed_objects)) {
RCLCPP_ERROR(get_logger(), "Failed transform to %s.", lanelet_frame_id_.c_str());
return;
}

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks! Fixed in the latest test.

},
"required": ["polygon_overlap_filter", "lanelet_direction_filter"]
"required": [
"polygon_overlap_filter",
"lanelet_direction_filter",
"debug",
"lanelet_extra_margin",
"use_height_threshold",
"max_height_threshold",
"min_height_threshold"
]
}
},
"required": ["filter_target_label", "filter_settings"],
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2022 TIER IV, Inc.

Check warning on line 1 in perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Overall Code Complexity

This module has a mean cyclomatic complexity of 4.14 across 14 functions. The mean complexity threshold is 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -66,6 +66,12 @@
filter_settings_.debug = declare_parameter<bool>("filter_settings.debug");
filter_settings_.lanelet_extra_margin =
declare_parameter<double>("filter_settings.lanelet_extra_margin");
filter_settings_.use_height_threshold =
declare_parameter<bool>("filter_settings.use_height_threshold");
filter_settings_.max_height_threshold =
declare_parameter<double>("filter_settings.max_height_threshold");
filter_settings_.min_height_threshold =
declare_parameter<double>("filter_settings.min_height_threshold");

// Set publisher/subscriber
map_sub_ = this->create_subscription<autoware_map_msgs::msg::LaneletMapBin>(
Expand Down Expand Up @@ -146,6 +152,17 @@
RCLCPP_ERROR(get_logger(), "Failed transform to %s.", lanelet_frame_id_.c_str());
return;
}
// vehicle base pose :map -> base_link
try {
ego_base_height_ = tf_buffer_
.lookupTransform(
lanelet_frame_id_, "base_link", transformed_objects.header.stamp,
rclcpp::Duration::from_seconds(0.5))
.transform.translation.z;
} catch (const tf2::TransformException & ex) {
RCLCPP_ERROR_STREAM(get_logger(), "Failed to get transform: " << ex.what());
return;
}

Check warning on line 165 in perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

ObjectLaneletFilterNode::objectCallback has a cyclomatic complexity of 9, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.

Check warning on line 165 in perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp#L165

Added line #L165 was not covered by tests
Copy link
Contributor

@badai-nguyen badai-nguyen Jan 22, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@YoshiRi
IMO, it is better to add condition of use_height_threshold here also

Suggested change
// vehicle base pose :map -> base_link
try {
ego_base_height_ = tf_buffer_
.lookupTransform(
lanelet_frame_id_, "base_link", transformed_objects.header.stamp,
rclcpp::Duration::from_seconds(0.5))
.transform.translation.z;
} catch (const tf2::TransformException & ex) {
RCLCPP_ERROR_STREAM(get_logger(), "Failed to get transform: " << ex.what());
return;
}
// vehicle base pose :map -> base_link
if (filter_settings_.use_height_threshold) {
try {
ego_base_height_ = tf_buffer_
.lookupTransform(
lanelet_frame_id_, "base_link", transformed_objects.header.stamp,
rclcpp::Duration::from_seconds(0.5))
.transform.translation.z;
} catch (const tf2::TransformException & ex) {
RCLCPP_ERROR_STREAM(get_logger(), "Failed to get transform: " << ex.what());
return;
}
}

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks! Fixed in 7206f1d.


if (!transformed_objects.objects.empty()) {
// calculate convex hull
Expand Down Expand Up @@ -199,6 +216,16 @@
return false;
}

// 0. check height threshold
if (filter_settings_.use_height_threshold) {
const double object_height = transformed_object.shape.dimensions.z;
if (
object_height > ego_base_height_ + filter_settings_.max_height_threshold ||
object_height < ego_base_height_ + filter_settings_.min_height_threshold) {
return false;
}
}

Check warning on line 228 in perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

ObjectLaneletFilterNode::filterObject increases in cyclomatic complexity from 9 to 12, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.

Check warning on line 228 in perception/autoware_detected_object_validation/src/lanelet_filter/lanelet_filter.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Bumpy Road Ahead

ObjectLaneletFilterNode::filterObject has 2 blocks with nested conditional logic. Any nesting of 2 or deeper is considered. Threshold is one single, nested block per function. The Bumpy Road code smell is a function that contains multiple chunks of nested conditional logic. The deeper the nesting and the more bumps, the lower the code health.
bool filter_pass = true;
// 1. is polygon overlap with road lanelets or shoulder lanelets
if (filter_settings_.polygon_overlap_filter) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@
#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>

#include <limits>
#include <memory>
#include <string>
#include <utility>
Expand Down Expand Up @@ -88,6 +89,7 @@ class ObjectLaneletFilterNode : public rclcpp::Node
tf2_ros::TransformListener tf_listener_;

utils::FilterTargetLabel filter_target_;
double ego_base_height_ = 0.0;
struct FilterSettings
{
bool polygon_overlap_filter;
Expand All @@ -96,6 +98,9 @@ class ObjectLaneletFilterNode : public rclcpp::Node
double lanelet_direction_filter_object_speed_threshold;
bool debug;
double lanelet_extra_margin;
bool use_height_threshold;
double max_height_threshold = std::numeric_limits<double>::infinity();
double min_height_threshold = -std::numeric_limits<double>::infinity();
} filter_settings_;

bool filterObject(
Expand Down
Loading
Loading