diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.cpp index 8d8afb41730f9..26479dc3b0b3b 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.cpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.cpp @@ -27,7 +27,7 @@ namespace behavior_velocity_planner::dynamic_obstacle_stop { std::optional find_closest_collision_point( - const EgoData & ego_data, const autoware_auto_perception_msgs::msg::PredictedObject & object, + const EgoData & ego_data, const autoware_perception_msgs::msg::PredictedObject & object, const tier4_autoware_utils::MultiPolygon2d & object_footprints, const PlannerParam & params) { std::optional closest_collision_point; @@ -74,7 +74,7 @@ std::optional find_closest_collision_point( std::vector find_collisions( const EgoData & ego_data, - const std::vector & objects, + const std::vector & objects, const std::vector & object_forward_footprints, const PlannerParam & params) { diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.hpp index ae66d79f110d5..119305a83a91e 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.hpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.hpp @@ -28,7 +28,7 @@ namespace behavior_velocity_planner::dynamic_obstacle_stop /// @param [in] object_footprint footprint of the object used for finding a collision /// @return the collision point closest to ego (if any) std::optional find_closest_collision_point( - const EgoData & ego_data, const autoware_auto_perception_msgs::msg::PredictedObject & object, + const EgoData & ego_data, const autoware_perception_msgs::msg::PredictedObject & object, const tier4_autoware_utils::MultiPolygon2d & object_footprints, const PlannerParam & params); /// @brief find the earliest collision along the ego path @@ -38,7 +38,7 @@ std::optional find_closest_collision_point( /// @return the point of earliest collision along the ego path std::vector find_collisions( const EgoData & ego_data, - const std::vector & objects, + const std::vector & objects, const std::vector & object_forward_footprints, const PlannerParam & params); diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.cpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.cpp index 9abcf2b7c1820..47640e6a35be9 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.cpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.cpp @@ -16,7 +16,7 @@ #include -#include +#include #include #include @@ -80,7 +80,7 @@ tier4_autoware_utils::Polygon2d create_footprint( } tier4_autoware_utils::MultiPolygon2d create_object_footprints( - const std::vector & objects, + const std::vector & objects, const PlannerParam & params) { tier4_autoware_utils::MultiPolygon2d footprints; diff --git a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.hpp b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.hpp index 9dc10c25eae47..b0f0fd64a96f4 100644 --- a/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.hpp +++ b/planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.hpp @@ -19,7 +19,7 @@ #include -#include +#include #include @@ -43,7 +43,7 @@ tier4_autoware_utils::Polygon2d make_forward_footprint( const autoware_perception_msgs::msg::PredictedObject & obstacle, const PlannerParam & params, const double hysteresis); tier4_autoware_utils::MultiPolygon2d create_object_footprints( - const std::vector & objects, + const std::vector & objects, const PlannerParam & params); tier4_autoware_utils::Polygon2d translate_polygon( const tier4_autoware_utils::Polygon2d & polygon, const double x, const double y);