@@ -28,8 +28,8 @@ namespace behavior_velocity_planner::dynamic_obstacle_stop
28
28
// / @param [in] object_footprint footprint of the object used for finding a collision
29
29
// / @return the collision point closest to ego (if any)
30
30
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);
33
33
34
34
// / @brief find the earliest collision along the ego path
35
35
// / @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(
39
39
std::vector<Collision> find_collisions (
40
40
const EgoData & ego_data,
41
41
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 ,
43
43
const PlannerParam & params);
44
44
45
45
} // namespace behavior_velocity_planner::dynamic_obstacle_stop
0 commit comments