Skip to content

Commit 994d075

Browse files
technolojinsaka1-s
authored andcommitted
feat(autoware_detected_object_validation): set validate distance in the obstacle pointcloud based validator (autowarefoundation#9663)
* chore: add validate_max_distance_m parameter for obstacle_pointcloud_based_validator Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * chore: optimize object distance validation in obstacle_pointcloud_validator Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * chore: add validate_max_distance_m parameter for obstacle_pointcloud_based_validator Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> --------- Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>
1 parent 60efdcc commit 994d075

File tree

3 files changed

+17
-0
lines changed

3 files changed

+17
-0
lines changed

perception/detected_object_validation/config/obstacle_pointcloud_based_validator.param.yaml

+2
Original file line numberDiff line numberDiff line change
@@ -12,5 +12,7 @@
1212
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN
1313
[800.0, 800.0, 800.0, 800.0, 800.0, 800.0, 800.0, 800.0]
1414

15+
validate_max_distance_m: 70.0 # [m]
16+
1517
using_2d_validator: false
1618
enable_debugger: false

perception/detected_object_validation/include/detected_object_validation/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -141,6 +141,7 @@ class ObstaclePointCloudBasedValidator : public rclcpp::Node
141141
typedef message_filters::Synchronizer<SyncPolicy> Sync;
142142
Sync sync_;
143143
PointsNumThresholdParam points_num_threshold_param_;
144+
double validate_max_distance_sq_; // maximum object distance to validate, squared [m^2]
144145

145146
std::shared_ptr<Debugger> debugger_;
146147
bool using_2d_validator_;

perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp

+14
Original file line numberDiff line numberDiff line change
@@ -288,6 +288,8 @@ ObstaclePointCloudBasedValidator::ObstaclePointCloudBasedValidator(
288288
declare_parameter<std::vector<int64_t>>("max_points_num");
289289
points_num_threshold_param_.min_points_and_distance_ratio =
290290
declare_parameter<std::vector<double>>("min_points_and_distance_ratio");
291+
const double validate_max_distance = declare_parameter<double>("validate_max_distance_m");
292+
validate_max_distance_sq_ = validate_max_distance * validate_max_distance;
291293

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

@@ -339,6 +341,18 @@ void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud(
339341
for (size_t i = 0; i < transformed_objects.objects.size(); ++i) {
340342
const auto & transformed_object = transformed_objects.objects.at(i);
341343
const auto & object = input_objects->objects.at(i);
344+
// check object distance
345+
const double distance_sq =
346+
transformed_object.kinematics.pose_with_covariance.pose.position.x *
347+
transformed_object.kinematics.pose_with_covariance.pose.position.x +
348+
transformed_object.kinematics.pose_with_covariance.pose.position.y *
349+
transformed_object.kinematics.pose_with_covariance.pose.position.y;
350+
if (distance_sq > validate_max_distance_sq_) {
351+
// pass to output
352+
output.objects.push_back(object);
353+
continue;
354+
}
355+
342356
const auto validated =
343357
validation_is_ready ? validator_->validate_object(transformed_object) : false;
344358
if (debugger_) {

0 commit comments

Comments
 (0)