Skip to content

Commit 149dff2

Browse files
author
beyza
committed
change function arguments
Signed-off-by: beyza <bnk@leodrive.ai>
1 parent 04d4f67 commit 149dff2

File tree

1 file changed

+3
-3
lines changed
  • planning/behavior_velocity_dynamic_obstacle_stop_module/src

1 file changed

+3
-3
lines changed

planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -28,8 +28,8 @@ namespace behavior_velocity_planner::dynamic_obstacle_stop
2828
/// @param [in] object_footprint footprint of the object used for finding a collision
2929
/// @return the collision point closest to ego (if any)
3030
std::optional<geometry_msgs::msg::Point> find_closest_collision_point(
31-
const EgoData & ego_data, const geometry_msgs::msg::Pose & object_pose,
32-
const tier4_autoware_utils::Polygon2d & object_footprint, const PlannerParam & params);
31+
const EgoData & ego_data, const autoware_auto_perception_msgs::msg::PredictedObject & object,
32+
const tier4_autoware_utils::MultiPolygon2d & object_footprints, const PlannerParam & params);
3333

3434
/// @brief find the earliest collision along the ego path
3535
/// @param [in] ego_data ego data including its path and footprint
@@ -39,7 +39,7 @@ std::optional<geometry_msgs::msg::Point> find_closest_collision_point(
3939
std::vector<Collision> find_collisions(
4040
const EgoData & ego_data,
4141
const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & objects,
42-
const tier4_autoware_utils::MultiPolygon2d & obstacle_forward_footprints,
42+
const std::vector<tier4_autoware_utils::MultiPolygon2d> & object_forward_footprints,
4343
const PlannerParam & params);
4444

4545
} // namespace behavior_velocity_planner::dynamic_obstacle_stop

0 commit comments

Comments
 (0)