Skip to content

Commit

Permalink
fix(planning_validator): remove syntax error in check_collision funct…
Browse files Browse the repository at this point in the history
…ion parameters

Signed-off-by: kyoichi-sugahara <[email protected]>
  • Loading branch information
kyoichi-sugahara committed Oct 31, 2024
1 parent 68dd4e2 commit 2936bfd
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ std::pair<double, size_t> calcMaxSteeringRates(
std::optional<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>> 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(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -562,8 +562,9 @@ 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) {
Expand Down
2 changes: 1 addition & 1 deletion planning/autoware_planning_validator/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -296,7 +296,7 @@ std::pair<double, size_t> calcMaxSteeringRates(
std::optional<std::vector<autoware_planning_msgs::msg::TrajectoryPoint>> 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<autoware_planning_msgs::msg::TrajectoryPoint> filtered_trajectory;
Expand Down

0 comments on commit 2936bfd

Please sign in to comment.