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): set validate distance in the obstacle pointcloud based validator #9663

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 @@ -12,5 +12,7 @@
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
[800.0, 800.0, 800.0, 800.0, 800.0, 800.0, 800.0, 800.0]

validate_max_distance_m: 70.0 # [m]

using_2d_validator: false
enable_debugger: false
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,11 @@
"default": [800, 800, 800, 800, 800, 800, 800, 800],
"description": "Threshold value of the number of point clouds per object when the distance from baselink is 1m, because the number of point clouds varies with the distance from baselink."
},
"validate_max_distance_m": {
"type": "number",
"default": 70.0,
"description": "The maximum distance from the baselink to the object to be validated"
},
"using_2d_validator": {
"type": "boolean",
"default": false,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -295,6 +295,8 @@
declare_parameter<std::vector<int64_t>>("max_points_num");
points_num_threshold_param_.min_points_and_distance_ratio =
declare_parameter<std::vector<double>>("min_points_and_distance_ratio");
const double validate_max_distance = declare_parameter<double>("validate_max_distance_m");
validate_max_distance_sq_ = validate_max_distance * validate_max_distance;

Check warning on line 299 in perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp#L298-L299

Added lines #L298 - L299 were not covered by tests

using_2d_validator_ = declare_parameter<bool>("using_2d_validator");

Expand Down Expand Up @@ -346,6 +348,18 @@
for (size_t i = 0; i < transformed_objects.objects.size(); ++i) {
const auto & transformed_object = transformed_objects.objects.at(i);
const auto & object = input_objects->objects.at(i);
// check object distance
const double distance_sq =
transformed_object.kinematics.pose_with_covariance.pose.position.x *

Check warning on line 353 in perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp#L352-L353

Added lines #L352 - L353 were not covered by tests
transformed_object.kinematics.pose_with_covariance.pose.position.x +
transformed_object.kinematics.pose_with_covariance.pose.position.y *

Check warning on line 355 in perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp#L355

Added line #L355 was not covered by tests
transformed_object.kinematics.pose_with_covariance.pose.position.y;
if (distance_sq > validate_max_distance_sq_) {
// pass to output
output.objects.push_back(object);
continue;

Check warning on line 360 in perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp#L359-L360

Added lines #L359 - L360 were not covered by tests
}

Check warning on line 362 in perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud has a cyclomatic complexity of 10, 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.
const auto validated =
validation_is_ready ? validator_->validate_object(transformed_object) : false;
if (debugger_) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -152,6 +152,7 @@ class ObstaclePointCloudBasedValidator : public rclcpp::Node
typedef message_filters::Synchronizer<SyncPolicy> Sync;
Sync sync_;
PointsNumThresholdParam points_num_threshold_param_;
double validate_max_distance_sq_; // maximum object distance to validate, squared [m^2]

std::shared_ptr<Debugger> debugger_;
bool using_2d_validator_;
Expand Down
Loading