From 33ea88ef7d437245a73eeb13cb14deb1e4a75469 Mon Sep 17 00:00:00 2001 From: kyoichi-sugahara Date: Fri, 1 Nov 2024 02:29:22 +0900 Subject: [PATCH] fix(planning_validator): remove syntax error in check_collision function parameters Signed-off-by: kyoichi-sugahara --- .../include/autoware/planning_validator/utils.hpp | 2 +- .../autoware_planning_validator/src/planning_validator.cpp | 4 ++-- planning/autoware_planning_validator/src/utils.cpp | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/planning/autoware_planning_validator/include/autoware/planning_validator/utils.hpp b/planning/autoware_planning_validator/include/autoware/planning_validator/utils.hpp index 864405c127a55..0d3e3bff7add3 100644 --- a/planning/autoware_planning_validator/include/autoware/planning_validator/utils.hpp +++ b/planning/autoware_planning_validator/include/autoware/planning_validator/utils.hpp @@ -76,7 +76,7 @@ std::pair calcMaxSteeringRates( std::optional> check_collision( const PredictedObjects & predicted_objects, const Trajectory & trajectory, const geometry_msgs::msg::Point & current_ego_position, const VehicleInfo & vehicle_info, - const double trajectory_to_object_distance_threshold, , + const double trajectory_to_object_distance_threshold, const double ego_to_object_distance_threshold, const double time_tolerance_threshold); Rtree make_ego_footprint_rtree( diff --git a/planning/autoware_planning_validator/src/planning_validator.cpp b/planning/autoware_planning_validator/src/planning_validator.cpp index e015689d9299c..5f04aebb9bf90 100644 --- a/planning/autoware_planning_validator/src/planning_validator.cpp +++ b/planning/autoware_planning_validator/src/planning_validator.cpp @@ -562,8 +562,8 @@ bool PlanningValidator::checkValidTrajectoryCollision(const Trajectory & traject const auto & collided_points = check_collision( *current_objects_, trajectory, current_kinematics_->pose.pose.position, vehicle_info_, - validator_params_.trajectory_to_object_distance_threshold, - validator_params_.ego_to_object_distance_threshold, validator_params_.time_tolerance_threshold); + validation_params_.trajectory_to_object_distance_threshold, + validation_params_.ego_to_object_distance_threshold, validation_params_.time_tolerance_threshold); if (collided_points) { for (const auto & p : *collided_points) { diff --git a/planning/autoware_planning_validator/src/utils.cpp b/planning/autoware_planning_validator/src/utils.cpp index 25c6f0d9d66ab..b12d104ed29d9 100644 --- a/planning/autoware_planning_validator/src/utils.cpp +++ b/planning/autoware_planning_validator/src/utils.cpp @@ -296,7 +296,7 @@ std::pair calcMaxSteeringRates( std::optional> check_collision( const PredictedObjects & predicted_objects, const Trajectory & trajectory, const geometry_msgs::msg::Point & current_ego_position, const VehicleInfo & vehicle_info, - const double trajectory_to_object_distance_threshold, , + const double trajectory_to_object_distance_threshold, const double ego_to_object_distance_threshold, const double time_tolerance_threshold) { std::vector filtered_trajectory;