From 00d82229b48d12d4b371cce4213a04e1f34f76ff Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi <93502286+zulfaqar-azmi-t4@users.noreply.github.com> Date: Tue, 30 Apr 2024 20:37:24 +0900 Subject: [PATCH] fix(bpp): change wrong function parameter's type for safety check (#6906) fix(bpp): change wrong function argument's type for safety check Signed-off-by: Muhammad Zulfaqar Azmi --- .../utils/path_safety_checker/safety_check.hpp | 4 ++-- .../src/utils/path_safety_checker/safety_check.cpp | 6 +++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp index 53c4706e49c10..f28685b2d914e 100644 --- a/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp +++ b/planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp @@ -54,11 +54,11 @@ bool isTargetObjectFront( Polygon2d createExtendedPolygon( const Pose & base_link_pose, const vehicle_info_util::VehicleInfo & vehicle_info, - const double lon_length, const double lat_margin, const double is_stopped_obj, + const double lon_length, const double lat_margin, const bool is_stopped_obj, CollisionCheckDebug & debug); Polygon2d createExtendedPolygon( const Pose & obj_pose, const Shape & shape, const double lon_length, const double lat_margin, - const double is_stopped_obj, CollisionCheckDebug & debug); + const bool is_stopped_obj, CollisionCheckDebug & debug); PredictedPath convertToPredictedPath( const std::vector & path, const double time_resolution); diff --git a/planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp b/planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp index 6390c45376b37..ceedb202209f3 100644 --- a/planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp +++ b/planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp @@ -90,7 +90,7 @@ bool isTargetObjectFront( Polygon2d createExtendedPolygon( const Pose & base_link_pose, const vehicle_info_util::VehicleInfo & vehicle_info, - const double lon_length, const double lat_margin, const double is_stopped_obj, + const double lon_length, const double lat_margin, const bool is_stopped_obj, CollisionCheckDebug & debug) { const double & base_to_front = vehicle_info.max_longitudinal_offset_m; @@ -131,7 +131,7 @@ Polygon2d createExtendedPolygon( Polygon2d createExtendedPolygon( const Pose & obj_pose, const Shape & shape, const double lon_length, const double lat_margin, - const double is_stopped_obj, CollisionCheckDebug & debug) + const bool is_stopped_obj, CollisionCheckDebug & debug) { const auto obj_polygon = tier4_autoware_utils::toPolygon2d(obj_pose, shape); if (obj_polygon.outer().empty()) { @@ -189,7 +189,7 @@ Polygon2d createExtendedPolygon( Polygon2d createExtendedPolygonAlongPath( const PathWithLaneId & planned_path, const Pose & base_link_pose, const vehicle_info_util::VehicleInfo & vehicle_info, const double lon_length, - const double lat_margin, const double is_stopped_obj, CollisionCheckDebug & debug) + const double lat_margin, const bool is_stopped_obj, CollisionCheckDebug & debug) { const double & base_to_front = vehicle_info.max_longitudinal_offset_m; const double & width = vehicle_info.vehicle_width_m;