Skip to content

Commit 178b6c0

Browse files
authored
feat(autoware_detected_object_validation): set validate distance in the obstacle pointcloud based validator (#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 fc2b93e commit 178b6c0

File tree

4 files changed

+22
-0
lines changed

4 files changed

+22
-0
lines changed

perception/autoware_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/autoware_detected_object_validation/schema/obstacle_pointcloud_based_validator.schema.json

+5
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,11 @@
3030
"default": [800, 800, 800, 800, 800, 800, 800, 800],
3131
"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."
3232
},
33+
"validate_max_distance_m": {
34+
"type": "number",
35+
"default": 70.0,
36+
"description": "The maximum distance from the baselink to the object to be validated"
37+
},
3338
"using_2d_validator": {
3439
"type": "boolean",
3540
"default": false,

perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp

+14
Original file line numberDiff line numberDiff line change
@@ -295,6 +295,8 @@ ObstaclePointCloudBasedValidator::ObstaclePointCloudBasedValidator(
295295
declare_parameter<std::vector<int64_t>>("max_points_num");
296296
points_num_threshold_param_.min_points_and_distance_ratio =
297297
declare_parameter<std::vector<double>>("min_points_and_distance_ratio");
298+
const double validate_max_distance = declare_parameter<double>("validate_max_distance_m");
299+
validate_max_distance_sq_ = validate_max_distance * validate_max_distance;
298300

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

@@ -346,6 +348,18 @@ void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud(
346348
for (size_t i = 0; i < transformed_objects.objects.size(); ++i) {
347349
const auto & transformed_object = transformed_objects.objects.at(i);
348350
const auto & object = input_objects->objects.at(i);
351+
// check object distance
352+
const double distance_sq =
353+
transformed_object.kinematics.pose_with_covariance.pose.position.x *
354+
transformed_object.kinematics.pose_with_covariance.pose.position.x +
355+
transformed_object.kinematics.pose_with_covariance.pose.position.y *
356+
transformed_object.kinematics.pose_with_covariance.pose.position.y;
357+
if (distance_sq > validate_max_distance_sq_) {
358+
// pass to output
359+
output.objects.push_back(object);
360+
continue;
361+
}
362+
349363
const auto validated =
350364
validation_is_ready ? validator_->validate_object(transformed_object) : false;
351365
if (debugger_) {

perception/autoware_detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -152,6 +152,7 @@ class ObstaclePointCloudBasedValidator : public rclcpp::Node
152152
typedef message_filters::Synchronizer<SyncPolicy> Sync;
153153
Sync sync_;
154154
PointsNumThresholdParam points_num_threshold_param_;
155+
double validate_max_distance_sq_; // maximum object distance to validate, squared [m^2]
155156

156157
std::shared_ptr<Debugger> debugger_;
157158
bool using_2d_validator_;

0 commit comments

Comments
 (0)