Skip to content

Commit f351fb6

Browse files
author
beyza
committed
update msg type
Signed-off-by: beyza <bnk@leodrive.ai>
1 parent 501b643 commit f351fb6

File tree

4 files changed

+8
-8
lines changed

4 files changed

+8
-8
lines changed

planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@
2727
namespace behavior_velocity_planner::dynamic_obstacle_stop
2828
{
2929
std::optional<geometry_msgs::msg::Point> find_closest_collision_point(
30-
const EgoData & ego_data, const autoware_auto_perception_msgs::msg::PredictedObject & object,
30+
const EgoData & ego_data, const autoware_perception_msgs::msg::PredictedObject & object,
3131
const tier4_autoware_utils::MultiPolygon2d & object_footprints, const PlannerParam & params)
3232
{
3333
std::optional<geometry_msgs::msg::Point> closest_collision_point;
@@ -74,7 +74,7 @@ std::optional<geometry_msgs::msg::Point> find_closest_collision_point(
7474

7575
std::vector<Collision> find_collisions(
7676
const EgoData & ego_data,
77-
const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & objects,
77+
const std::vector<autoware_perception_msgs::msg::PredictedObject> & objects,
7878
const std::vector<tier4_autoware_utils::MultiPolygon2d> & object_forward_footprints,
7979
const PlannerParam & params)
8080
{

planning/behavior_velocity_dynamic_obstacle_stop_module/src/collision.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,7 @@ 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 autoware_auto_perception_msgs::msg::PredictedObject & object,
31+
const EgoData & ego_data, const autoware_perception_msgs::msg::PredictedObject & object,
3232
const tier4_autoware_utils::MultiPolygon2d & object_footprints, const PlannerParam & params);
3333

3434
/// @brief find the earliest collision along the ego path
@@ -38,7 +38,7 @@ std::optional<geometry_msgs::msg::Point> find_closest_collision_point(
3838
/// @return the point of earliest collision along the ego path
3939
std::vector<Collision> find_collisions(
4040
const EgoData & ego_data,
41-
const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & objects,
41+
const std::vector<autoware_perception_msgs::msg::PredictedObject> & objects,
4242
const std::vector<tier4_autoware_utils::MultiPolygon2d> & object_forward_footprints,
4343
const PlannerParam & params);
4444

planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,7 @@
1616

1717
#include <tier4_autoware_utils/geometry/boost_polygon_utils.hpp>
1818

19-
#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>
19+
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
2020
#include <geometry_msgs/msg/pose.hpp>
2121

2222
#include <boost/geometry.hpp>
@@ -80,7 +80,7 @@ tier4_autoware_utils::Polygon2d create_footprint(
8080
}
8181

8282
tier4_autoware_utils::MultiPolygon2d create_object_footprints(
83-
const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & objects,
83+
const std::vector<autoware_perception_msgs::msg::PredictedObject> & objects,
8484
const PlannerParam & params)
8585
{
8686
tier4_autoware_utils::MultiPolygon2d footprints;

planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@
1919

2020
#include <tier4_autoware_utils/geometry/geometry.hpp>
2121

22-
#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>
22+
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
2323

2424
#include <vector>
2525

@@ -43,7 +43,7 @@ tier4_autoware_utils::Polygon2d make_forward_footprint(
4343
const autoware_perception_msgs::msg::PredictedObject & obstacle, const PlannerParam & params,
4444
const double hysteresis);
4545
tier4_autoware_utils::MultiPolygon2d create_object_footprints(
46-
const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & objects,
46+
const std::vector<autoware_perception_msgs::msg::PredictedObject> & objects,
4747
const PlannerParam & params);
4848
tier4_autoware_utils::Polygon2d translate_polygon(
4949
const tier4_autoware_utils::Polygon2d & polygon, const double x, const double y);

0 commit comments

Comments
 (0)