|
15 | 15 | #include "calculate_slowdown_points.hpp"
|
16 | 16 |
|
17 | 17 | #include "footprint.hpp"
|
| 18 | +#include "types.hpp" |
18 | 19 |
|
19 | 20 | #include <autoware/motion_utils/trajectory/interpolation.hpp>
|
20 | 21 | #include <autoware/motion_utils/trajectory/trajectory.hpp>
|
| 22 | +#include <autoware/universe_utils/geometry/boost_geometry.hpp> |
21 | 23 |
|
22 |
| -#include <boost/geometry/algorithms/overlaps.hpp> |
| 24 | +#include <autoware_planning_msgs/msg/detail/trajectory_point__struct.hpp> |
| 25 | +#include <geometry_msgs/msg/detail/pose__struct.hpp> |
| 26 | +#include <geometry_msgs/msg/pose.hpp> |
23 | 27 |
|
| 28 | +#include <boost/geometry/algorithms/disjoint.hpp> |
| 29 | + |
| 30 | +#include <lanelet2_core/Forward.h> |
24 | 31 | #include <lanelet2_core/geometry/Polygon.h>
|
25 | 32 |
|
| 33 | +#include <algorithm> |
| 34 | +#include <optional> |
| 35 | +#include <vector> |
| 36 | + |
26 | 37 | namespace autoware::motion_velocity_planner::out_of_lane
|
27 | 38 | {
|
28 | 39 |
|
29 |
| -bool can_decelerate( |
30 |
| - const EgoData & ego_data, const TrajectoryPoint & point, const double target_vel) |
| 40 | +std::optional<geometry_msgs::msg::Pose> calculate_last_avoiding_pose( |
| 41 | + const std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & trajectory, |
| 42 | + const universe_utils::Polygon2d & footprint, const lanelet::BasicPolygons2d & polygons_to_avoid, |
| 43 | + const double min_arc_length, const double max_arc_length, const double precision) |
31 | 44 | {
|
32 |
| - // TODO(Maxime): use the library function |
33 |
| - const auto dist_ahead_of_ego = autoware::motion_utils::calcSignedArcLength( |
34 |
| - ego_data.trajectory_points, ego_data.pose.position, point.pose.position); |
35 |
| - const auto acc_to_target_vel = |
36 |
| - (ego_data.velocity * ego_data.velocity - target_vel * target_vel) / (2 * dist_ahead_of_ego); |
37 |
| - return acc_to_target_vel < std::abs(ego_data.max_decel); |
| 45 | + geometry_msgs::msg::Pose interpolated_pose{}; |
| 46 | + bool is_avoiding_pose = false; |
| 47 | + |
| 48 | + auto from = min_arc_length; |
| 49 | + auto to = max_arc_length; |
| 50 | + while (to - from > precision) { |
| 51 | + auto l = from + 0.5 * (to - from); |
| 52 | + interpolated_pose = motion_utils::calcInterpolatedPose(trajectory, l); |
| 53 | + const auto interpolated_footprint = project_to_pose(footprint, interpolated_pose); |
| 54 | + is_avoiding_pose = |
| 55 | + std::all_of(polygons_to_avoid.begin(), polygons_to_avoid.end(), [&](const auto & polygon) { |
| 56 | + return boost::geometry::disjoint(interpolated_footprint, polygon); |
| 57 | + }); |
| 58 | + if (is_avoiding_pose) { |
| 59 | + from = l; |
| 60 | + } else { |
| 61 | + to = l; |
| 62 | + } |
| 63 | + } |
| 64 | + if (is_avoiding_pose) { |
| 65 | + return interpolated_pose; |
| 66 | + } |
| 67 | + return std::nullopt; |
38 | 68 | }
|
39 | 69 |
|
40 |
| -std::optional<TrajectoryPoint> calculate_last_in_lane_pose( |
41 |
| - const EgoData & ego_data, const Slowdown & decision, |
42 |
| - const autoware::universe_utils::Polygon2d & footprint, |
43 |
| - const std::optional<SlowdownToInsert> & prev_slowdown_point, const PlannerParam & params) |
| 70 | +std::optional<geometry_msgs::msg::Pose> calculate_pose_ahead_of_collision( |
| 71 | + const EgoData & ego_data, const OutOfLanePoint & point_to_avoid, |
| 72 | + const universe_utils::Polygon2d & footprint, const double precision) |
44 | 73 | {
|
45 |
| - const auto from_arc_length = autoware::motion_utils::calcSignedArcLength( |
46 |
| - ego_data.trajectory_points, 0, ego_data.first_trajectory_idx); |
47 |
| - const auto to_arc_length = autoware::motion_utils::calcSignedArcLength( |
48 |
| - ego_data.trajectory_points, 0, decision.target_trajectory_idx); |
49 |
| - TrajectoryPoint interpolated_point; |
50 |
| - for (auto l = to_arc_length - params.precision; l > from_arc_length; l -= params.precision) { |
51 |
| - // TODO(Maxime): binary search |
52 |
| - interpolated_point.pose = |
53 |
| - autoware::motion_utils::calcInterpolatedPose(ego_data.trajectory_points, l); |
54 |
| - const auto respect_decel_limit = |
55 |
| - !params.skip_if_over_max_decel || prev_slowdown_point || |
56 |
| - can_decelerate(ego_data, interpolated_point, decision.velocity); |
57 |
| - const auto interpolated_footprint = project_to_pose(footprint, interpolated_point.pose); |
58 |
| - const auto is_overlap_lane = boost::geometry::overlaps( |
59 |
| - interpolated_footprint, decision.lane_to_avoid.polygon2d().basicPolygon()); |
60 |
| - const auto is_overlap_extra_lane = |
61 |
| - prev_slowdown_point && |
62 |
| - boost::geometry::overlaps( |
63 |
| - interpolated_footprint, |
64 |
| - prev_slowdown_point->slowdown.lane_to_avoid.polygon2d().basicPolygon()); |
65 |
| - if (respect_decel_limit && !is_overlap_lane && !is_overlap_extra_lane) |
66 |
| - return interpolated_point; |
| 74 | + const auto first_avoid_arc_length = motion_utils::calcSignedArcLength( |
| 75 | + ego_data.trajectory_points, 0UL, point_to_avoid.trajectory_index); |
| 76 | + for (auto l = first_avoid_arc_length - precision; l >= ego_data.min_stop_arc_length; |
| 77 | + l -= precision) { |
| 78 | + const auto interpolated_pose = |
| 79 | + motion_utils::calcInterpolatedPose(ego_data.trajectory_points, l); |
| 80 | + const auto interpolated_footprint = project_to_pose(footprint, interpolated_pose); |
| 81 | + if (boost::geometry::intersects(interpolated_footprint, point_to_avoid.outside_ring)) { |
| 82 | + return interpolated_pose; |
| 83 | + } |
67 | 84 | }
|
68 | 85 | return std::nullopt;
|
69 | 86 | }
|
70 | 87 |
|
71 |
| -std::optional<SlowdownToInsert> calculate_slowdown_point( |
72 |
| - const EgoData & ego_data, const std::vector<Slowdown> & decisions, |
73 |
| - const std::optional<SlowdownToInsert> & prev_slowdown_point, PlannerParam params) |
| 88 | +std::optional<geometry_msgs::msg::Pose> calculate_slowdown_point( |
| 89 | + const EgoData & ego_data, const OutOfLaneData & out_of_lane_data, PlannerParam params) |
74 | 90 | {
|
| 91 | + const auto point_to_avoid_it = std::find_if( |
| 92 | + out_of_lane_data.outside_points.cbegin(), out_of_lane_data.outside_points.cend(), |
| 93 | + [&](const auto & p) { return p.to_avoid; }); |
| 94 | + if (point_to_avoid_it == out_of_lane_data.outside_points.cend()) { |
| 95 | + return std::nullopt; |
| 96 | + } |
| 97 | + const auto raw_footprint = make_base_footprint(params, true); // ignore extra footprint offsets |
| 98 | + const auto base_footprint = make_base_footprint(params); |
75 | 99 | params.extra_front_offset += params.lon_dist_buffer;
|
76 | 100 | params.extra_right_offset += params.lat_dist_buffer;
|
77 | 101 | params.extra_left_offset += params.lat_dist_buffer;
|
78 |
| - const auto base_footprint = make_base_footprint(params); |
| 102 | + const auto expanded_footprint = make_base_footprint(params); // with added distance buffers |
| 103 | + lanelet::BasicPolygons2d polygons_to_avoid; |
| 104 | + for (const auto & ll : point_to_avoid_it->overlapped_lanelets) { |
| 105 | + polygons_to_avoid.push_back(ll.polygon2d().basicPolygon()); |
| 106 | + } |
| 107 | + // points are ordered by trajectory index so the first one has the smallest index and arc length |
| 108 | + const auto first_outside_idx = out_of_lane_data.outside_points.front().trajectory_index; |
| 109 | + const auto first_outside_arc_length = |
| 110 | + motion_utils::calcSignedArcLength(ego_data.trajectory_points, 0UL, first_outside_idx); |
79 | 111 |
|
| 112 | + std::optional<geometry_msgs::msg::Pose> slowdown_point; |
80 | 113 | // search for the first slowdown decision for which a stop point can be inserted
|
81 |
| - for (const auto & decision : decisions) { |
82 |
| - const auto last_in_lane_pose = |
83 |
| - calculate_last_in_lane_pose(ego_data, decision, base_footprint, prev_slowdown_point, params); |
84 |
| - if (last_in_lane_pose) return SlowdownToInsert{decision, *last_in_lane_pose}; |
| 114 | + // we first try to use the expanded footprint (distance buffers + extra footprint offsets) |
| 115 | + for (const auto & footprint : {expanded_footprint, base_footprint, raw_footprint}) { |
| 116 | + slowdown_point = calculate_last_avoiding_pose( |
| 117 | + ego_data.trajectory_points, footprint, polygons_to_avoid, ego_data.min_stop_arc_length, |
| 118 | + first_outside_arc_length, params.precision); |
| 119 | + if (slowdown_point) { |
| 120 | + break; |
| 121 | + } |
85 | 122 | }
|
86 |
| - return std::nullopt; |
| 123 | + // fallback to simply stopping ahead of the collision to avoid (regardless of being out of lane or |
| 124 | + // not) |
| 125 | + if (!slowdown_point) { |
| 126 | + slowdown_point = calculate_pose_ahead_of_collision( |
| 127 | + ego_data, *point_to_avoid_it, expanded_footprint, params.precision); |
| 128 | + } |
| 129 | + return slowdown_point; |
87 | 130 | }
|
88 | 131 | } // namespace autoware::motion_velocity_planner::out_of_lane
|
0 commit comments