Skip to content

Commit 00d8222

Browse files
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 <zulfaqar.azmi@tier4.jp>
1 parent b630838 commit 00d8222

File tree

2 files changed

+5
-5
lines changed
  • planning/behavior_path_planner_common

2 files changed

+5
-5
lines changed

planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -54,11 +54,11 @@ bool isTargetObjectFront(
5454

5555
Polygon2d createExtendedPolygon(
5656
const Pose & base_link_pose, const vehicle_info_util::VehicleInfo & vehicle_info,
57-
const double lon_length, const double lat_margin, const double is_stopped_obj,
57+
const double lon_length, const double lat_margin, const bool is_stopped_obj,
5858
CollisionCheckDebug & debug);
5959
Polygon2d createExtendedPolygon(
6060
const Pose & obj_pose, const Shape & shape, const double lon_length, const double lat_margin,
61-
const double is_stopped_obj, CollisionCheckDebug & debug);
61+
const bool is_stopped_obj, CollisionCheckDebug & debug);
6262

6363
PredictedPath convertToPredictedPath(
6464
const std::vector<PoseWithVelocityStamped> & path, const double time_resolution);

planning/behavior_path_planner_common/src/utils/path_safety_checker/safety_check.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -90,7 +90,7 @@ bool isTargetObjectFront(
9090

9191
Polygon2d createExtendedPolygon(
9292
const Pose & base_link_pose, const vehicle_info_util::VehicleInfo & vehicle_info,
93-
const double lon_length, const double lat_margin, const double is_stopped_obj,
93+
const double lon_length, const double lat_margin, const bool is_stopped_obj,
9494
CollisionCheckDebug & debug)
9595
{
9696
const double & base_to_front = vehicle_info.max_longitudinal_offset_m;
@@ -131,7 +131,7 @@ Polygon2d createExtendedPolygon(
131131

132132
Polygon2d createExtendedPolygon(
133133
const Pose & obj_pose, const Shape & shape, const double lon_length, const double lat_margin,
134-
const double is_stopped_obj, CollisionCheckDebug & debug)
134+
const bool is_stopped_obj, CollisionCheckDebug & debug)
135135
{
136136
const auto obj_polygon = tier4_autoware_utils::toPolygon2d(obj_pose, shape);
137137
if (obj_polygon.outer().empty()) {
@@ -189,7 +189,7 @@ Polygon2d createExtendedPolygon(
189189
Polygon2d createExtendedPolygonAlongPath(
190190
const PathWithLaneId & planned_path, const Pose & base_link_pose,
191191
const vehicle_info_util::VehicleInfo & vehicle_info, const double lon_length,
192-
const double lat_margin, const double is_stopped_obj, CollisionCheckDebug & debug)
192+
const double lat_margin, const bool is_stopped_obj, CollisionCheckDebug & debug)
193193
{
194194
const double & base_to_front = vehicle_info.max_longitudinal_offset_m;
195195
const double & width = vehicle_info.vehicle_width_m;

0 commit comments

Comments
 (0)