Skip to content

Commit

Permalink
update msg type
Browse files Browse the repository at this point in the history
Signed-off-by: beyza <[email protected]>
  • Loading branch information
beyzanurkaya committed Jun 5, 2024
1 parent 501b643 commit f351fb6
Show file tree
Hide file tree
Showing 4 changed files with 8 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
namespace behavior_velocity_planner::dynamic_obstacle_stop
{
std::optional<geometry_msgs::msg::Point> 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<geometry_msgs::msg::Point> closest_collision_point;
Expand Down Expand Up @@ -74,7 +74,7 @@ std::optional<geometry_msgs::msg::Point> find_closest_collision_point(

std::vector<Collision> find_collisions(
const EgoData & ego_data,
const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & objects,
const std::vector<autoware_perception_msgs::msg::PredictedObject> & objects,
const std::vector<tier4_autoware_utils::MultiPolygon2d> & object_forward_footprints,
const PlannerParam & params)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<geometry_msgs::msg::Point> 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
Expand All @@ -38,7 +38,7 @@ std::optional<geometry_msgs::msg::Point> find_closest_collision_point(
/// @return the point of earliest collision along the ego path
std::vector<Collision> find_collisions(
const EgoData & ego_data,
const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & objects,
const std::vector<autoware_perception_msgs::msg::PredictedObject> & objects,
const std::vector<tier4_autoware_utils::MultiPolygon2d> & object_forward_footprints,
const PlannerParam & params);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

#include <tier4_autoware_utils/geometry/boost_polygon_utils.hpp>

#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
#include <geometry_msgs/msg/pose.hpp>

#include <boost/geometry.hpp>
Expand Down Expand Up @@ -80,7 +80,7 @@ tier4_autoware_utils::Polygon2d create_footprint(
}

tier4_autoware_utils::MultiPolygon2d create_object_footprints(
const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & objects,
const std::vector<autoware_perception_msgs::msg::PredictedObject> & objects,
const PlannerParam & params)
{
tier4_autoware_utils::MultiPolygon2d footprints;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

#include <tier4_autoware_utils/geometry/geometry.hpp>

#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>
#include <autoware_perception_msgs/msg/predicted_objects.hpp>

#include <vector>

Expand All @@ -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<autoware_auto_perception_msgs::msg::PredictedObject> & objects,
const std::vector<autoware_perception_msgs::msg::PredictedObject> & objects,
const PlannerParam & params);
tier4_autoware_utils::Polygon2d translate_polygon(
const tier4_autoware_utils::Polygon2d & polygon, const double x, const double y);
Expand Down

0 comments on commit f351fb6

Please sign in to comment.