Skip to content

Commit be2299d

Browse files
author
beyza
committed
create object's predicted_footprint
Signed-off-by: beyza <bnk@leodrive.ai>
1 parent 3d782f2 commit be2299d

File tree

2 files changed

+46
-0
lines changed

2 files changed

+46
-0
lines changed

planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.cpp

+41
Original file line numberDiff line numberDiff line change
@@ -14,8 +14,10 @@
1414

1515
#include "footprint.hpp"
1616

17+
#include <motion_utils/trajectory/trajectory.hpp>
1718
#include <tier4_autoware_utils/geometry/boost_polygon_utils.hpp>
1819

20+
#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>
1921
#include <geometry_msgs/msg/pose.hpp>
2022

2123
#include <boost/geometry/algorithms/envelope.hpp>
@@ -28,6 +30,7 @@
2830

2931
namespace behavior_velocity_planner::dynamic_obstacle_stop
3032
{
33+
using Point2d = tier4_autoware_utils::Point2d;
3134
tier4_autoware_utils::MultiPolygon2d make_forward_footprints(
3235
const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & obstacles,
3336
const PlannerParam & params, const double hysteresis)
@@ -58,6 +61,44 @@ tier4_autoware_utils::Polygon2d make_forward_footprint(
5861
{}};
5962
}
6063

64+
//create footprint using predicted_path of object
65+
tier4_autoware_utils::Polygon2d translate_polygon(const tier4_autoware_utils::Polygon2d & polygon, const double x, const double y)
66+
{
67+
tier4_autoware_utils::Polygon2d translated_polygon;
68+
const boost::geometry::strategy::transform::translate_transformer<double, 2, 2> translation(x, y);
69+
boost::geometry::transform(polygon, translated_polygon, translation);
70+
return translated_polygon;
71+
}
72+
73+
tier4_autoware_utils::Polygon2d create_footprint(const geometry_msgs::msg::Pose & pose, const tier4_autoware_utils::Polygon2d& base_footprint)
74+
{
75+
const auto angle = tf2::getYaw(pose.orientation);
76+
return translate_polygon(
77+
tier4_autoware_utils::rotatePolygon(base_footprint, angle), pose.position.x, pose.position.y);
78+
}
79+
80+
tier4_autoware_utils::MultiPolygon2d create_object_footprints(
81+
const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & objects, const PlannerParam & params)
82+
{
83+
tier4_autoware_utils::MultiPolygon2d footprints;
84+
85+
for (const auto & object : objects) {
86+
const auto front = object.shape.dimensions.x / 2 + params.extra_object_width;
87+
const auto rear = -object.shape.dimensions.x / 2 - params.extra_object_width;
88+
const auto left = object.shape.dimensions.y / 2 + params.extra_object_width;
89+
const auto right = -object.shape.dimensions.y / 2 - params.extra_object_width;
90+
tier4_autoware_utils::Polygon2d base_footprint;
91+
base_footprint.outer() = {
92+
Point2d{front, left}, Point2d{front, right}, Point2d{rear, right}, Point2d{rear, left},
93+
Point2d{front, left}};
94+
for (const auto & path : object.kinematics.predicted_paths)
95+
for (const auto & pose : path.path)
96+
footprints.push_back(create_footprint(pose, base_footprint));
97+
}
98+
99+
return footprints;
100+
}
101+
61102
tier4_autoware_utils::Polygon2d project_to_pose(
62103
const tier4_autoware_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose)
63104
{

planning/behavior_velocity_dynamic_obstacle_stop_module/src/footprint.hpp

+5
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#include "types.hpp"
1919

2020
#include <tier4_autoware_utils/geometry/geometry.hpp>
21+
#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>
2122

2223
#include <vector>
2324

@@ -40,6 +41,10 @@ tier4_autoware_utils::MultiPolygon2d make_forward_footprints(
4041
tier4_autoware_utils::Polygon2d make_forward_footprint(
4142
const autoware_auto_perception_msgs::msg::PredictedObject & obstacle, const PlannerParam & params,
4243
const double hysteresis);
44+
tier4_autoware_utils::MultiPolygon2d create_object_footprints(
45+
const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & objects, const PlannerParam & params);
46+
tier4_autoware_utils::Polygon2d translate_polygon(const tier4_autoware_utils::Polygon2d & polygon, const double x, const double y);
47+
tier4_autoware_utils::Polygon2d create_footprint(const geometry_msgs::msg::Pose & pose, const tier4_autoware_utils::Polygon2d& base_footprint);
4348
/// @brief project a footprint to the given pose
4449
/// @param [in] base_footprint footprint to project
4550
/// @param [in] pose projection pose

0 commit comments

Comments
 (0)