|
14 | 14 |
|
15 | 15 | #include "footprint.hpp"
|
16 | 16 |
|
| 17 | +#include <motion_utils/trajectory/trajectory.hpp> |
17 | 18 | #include <tier4_autoware_utils/geometry/boost_polygon_utils.hpp>
|
18 | 19 |
|
| 20 | +#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp> |
19 | 21 | #include <geometry_msgs/msg/pose.hpp>
|
20 | 22 |
|
21 | 23 | #include <boost/geometry/algorithms/envelope.hpp>
|
|
28 | 30 |
|
29 | 31 | namespace behavior_velocity_planner::dynamic_obstacle_stop
|
30 | 32 | {
|
| 33 | +using Point2d = tier4_autoware_utils::Point2d; |
31 | 34 | tier4_autoware_utils::MultiPolygon2d make_forward_footprints(
|
32 | 35 | const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & obstacles,
|
33 | 36 | const PlannerParam & params, const double hysteresis)
|
@@ -58,6 +61,44 @@ tier4_autoware_utils::Polygon2d make_forward_footprint(
|
58 | 61 | {}};
|
59 | 62 | }
|
60 | 63 |
|
| 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 | + |
61 | 102 | tier4_autoware_utils::Polygon2d project_to_pose(
|
62 | 103 | const tier4_autoware_utils::Polygon2d & base_footprint, const geometry_msgs::msg::Pose & pose)
|
63 | 104 | {
|
|
0 commit comments