Skip to content

Commit

Permalink
fix(bpp): change wrong function parameter's type for safety check (#6906
Browse files Browse the repository at this point in the history
)

fix(bpp): change wrong function argument's type for safety check

Signed-off-by: Muhammad Zulfaqar Azmi <[email protected]>
  • Loading branch information
zulfaqar-azmi-t4 authored Apr 30, 2024
1 parent b630838 commit 00d8222
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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<PoseWithVelocityStamped> & path, const double time_resolution);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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()) {
Expand Down Expand Up @@ -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;
Expand Down

0 comments on commit 00d8222

Please sign in to comment.