Skip to content

Commit c0644c3

Browse files
maxime-clemxtk8532704saka1-s
authored
feat(out_of_lane): redesign (#1509)
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp> Co-authored-by: Tiankui Xian <1041084556@qq.com> Co-authored-by: Shohei Sakai <saka1s.jp@gmail.com>
1 parent da8b050 commit c0644c3

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

43 files changed

+1412
-1517
lines changed

common/autoware_motion_utils/include/autoware/motion_utils/trajectory/trajectory.hpp

+9
Original file line numberDiff line numberDiff line change
@@ -2504,6 +2504,15 @@ extern template bool isTargetPointFront<std::vector<autoware_planning_msgs::msg:
25042504
const geometry_msgs::msg::Point & base_point, const geometry_msgs::msg::Point & target_point,
25052505
const double threshold = 0.0);
25062506

2507+
/// @brief calculate the time_from_start fields of the given trajectory points
2508+
/// @details this function assumes constant longitudinal velocity between points
2509+
/// @param trajectory trajectory for which to calculate the time_from_start
2510+
/// @param current_ego_point current ego position
2511+
/// @param min_velocity minimum velocity used for a trajectory point
2512+
void calculate_time_from_start(
2513+
std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & trajectory,
2514+
const geometry_msgs::msg::Point & current_ego_point, const float min_velocity = 1.0f);
2515+
25072516
} // namespace autoware::motion_utils
25082517

25092518
#endif // AUTOWARE__MOTION_UTILS__TRAJECTORY__TRAJECTORY_HPP_

common/autoware_motion_utils/src/trajectory/trajectory.cpp

+23
Original file line numberDiff line numberDiff line change
@@ -599,4 +599,27 @@ template bool isTargetPointFront<std::vector<autoware_planning_msgs::msg::Trajec
599599
const geometry_msgs::msg::Point & base_point, const geometry_msgs::msg::Point & target_point,
600600
const double threshold);
601601

602+
void calculate_time_from_start(
603+
std::vector<autoware_planning_msgs::msg::TrajectoryPoint> & trajectory,
604+
const geometry_msgs::msg::Point & current_ego_point, const float min_velocity)
605+
{
606+
const auto nearest_segment_idx = findNearestSegmentIndex(trajectory, current_ego_point);
607+
if (nearest_segment_idx + 1 == trajectory.size()) {
608+
return;
609+
}
610+
for (auto & p : trajectory) {
611+
p.time_from_start = rclcpp::Duration::from_seconds(0);
612+
}
613+
// TODO(Maxime): some points can have very low velocities which introduce huge time errors
614+
// Temporary solution: use a minimum velocity
615+
for (auto idx = nearest_segment_idx + 1; idx < trajectory.size(); ++idx) {
616+
const auto & from = trajectory[idx - 1];
617+
const auto velocity = std::max(min_velocity, from.longitudinal_velocity_mps);
618+
if (velocity != 0.0) {
619+
auto & to = trajectory[idx];
620+
const auto t = universe_utils::calcDistance2d(from, to) / velocity;
621+
to.time_from_start = rclcpp::Duration::from_seconds(t) + from.time_from_start;
622+
}
623+
}
624+
}
602625
} // namespace autoware::motion_utils

planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/README.md

+84-107
Large diffs are not rendered by default.
Original file line numberDiff line numberDiff line change
@@ -1,32 +1,22 @@
11
/**:
22
ros__parameters:
33
out_of_lane: # module to stop or slowdown before overlapping another lane with other objects
4-
mode: ttc # mode used to consider a conflict with an object. "threshold", "intervals", or "ttc"
4+
mode: ttc # mode used to consider a conflict with an object. "threshold", or "ttc"
55
skip_if_already_overlapping: true # do not run this module when ego already overlaps another lane
6+
max_arc_length: 100.0 # [m] maximum trajectory arc length that is checked for out_of_lane collisions
67

78
threshold:
89
time_threshold: 5.0 # [s] consider objects that will reach an overlap within this time
9-
intervals: # consider objects if their estimated time interval spent on the overlap intersect the estimated time interval of ego
10-
ego_time_buffer: 0.5 # [s] extend the ego time interval by this buffer
11-
objects_time_buffer: 0.5 # [s] extend the time intervals of objects by this buffer
1210
ttc:
1311
threshold: 3.0 # [s] consider objects with an estimated time to collision bellow this value while on the overlap
1412

1513
objects:
1614
minimum_velocity: 0.5 # [m/s] objects lower than this velocity will be ignored
17-
use_predicted_paths: true # if true, use the predicted paths to estimate future positions.
18-
# if false, assume the object moves at constant velocity along *all* lanelets it currently is located in.
1915
predicted_path_min_confidence : 0.1 # when using predicted paths, ignore the ones whose confidence is lower than this value.
20-
distance_buffer: 1.0 # [m] distance buffer used to determine if a collision will occur in the other lane
2116
cut_predicted_paths_beyond_red_lights: true # if true, predicted paths are cut beyond the stop line of red traffic lights
2217
ignore_behind_ego: true # if true, objects behind the ego vehicle are ignored
2318

24-
overlap:
25-
minimum_distance: 0.0 # [m] minimum distance inside a lanelet for an overlap to be considered
26-
extra_length: 0.0 # [m] extra arc length to add to the front and back of an overlap (used to calculate enter/exit times)
27-
2819
action: # action to insert in the trajectory if an object causes a conflict at an overlap
29-
skip_if_over_max_decel: true # if true, do not take an action that would cause more deceleration than the maximum allowed
3020
precision: 0.1 # [m] precision when inserting a stop pose in the trajectory
3121
longitudinal_distance_buffer: 1.5 # [m] safety distance buffer to keep in front of the ego vehicle
3222
lateral_distance_buffer: 1.0 # [m] safety distance buffer to keep on the side of the ego vehicle
@@ -38,8 +28,8 @@
3828
distance_threshold: 15.0 # [m] insert a stop when closer than this distance from an overlap
3929

4030
ego:
41-
min_assumed_velocity: 2.0 # [m/s] minimum velocity used to calculate the enter and exit times of ego
42-
extra_front_offset: 0.0 # [m] extra front distance
43-
extra_rear_offset: 0.0 # [m] extra rear distance
44-
extra_right_offset: 0.0 # [m] extra right distance
45-
extra_left_offset: 0.0 # [m] extra left distance
31+
# extra footprint offsets to calculate out of lane collisions
32+
extra_front_offset: 0.0 # [m] extra footprint front distance
33+
extra_rear_offset: 0.0 # [m] extra footprint rear distance
34+
extra_right_offset: 0.0 # [m] extra footprint right distance
35+
extra_left_offset: 0.0 # [m] extra footprint left distance
Loading

planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.cpp

+87-44
Original file line numberDiff line numberDiff line change
@@ -15,74 +15,117 @@
1515
#include "calculate_slowdown_points.hpp"
1616

1717
#include "footprint.hpp"
18+
#include "types.hpp"
1819

1920
#include <autoware/motion_utils/trajectory/interpolation.hpp>
2021
#include <autoware/motion_utils/trajectory/trajectory.hpp>
22+
#include <autoware/universe_utils/geometry/boost_geometry.hpp>
2123

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>
2327

28+
#include <boost/geometry/algorithms/disjoint.hpp>
29+
30+
#include <lanelet2_core/Forward.h>
2431
#include <lanelet2_core/geometry/Polygon.h>
2532

33+
#include <algorithm>
34+
#include <optional>
35+
#include <vector>
36+
2637
namespace autoware::motion_velocity_planner::out_of_lane
2738
{
2839

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)
3144
{
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;
3868
}
3969

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)
4473
{
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+
}
6784
}
6885
return std::nullopt;
6986
}
7087

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)
7490
{
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);
7599
params.extra_front_offset += params.lon_dist_buffer;
76100
params.extra_right_offset += params.lat_dist_buffer;
77101
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);
79111

112+
std::optional<geometry_msgs::msg::Pose> slowdown_point;
80113
// 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+
}
85122
}
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;
87130
}
88131
} // namespace autoware::motion_velocity_planner::out_of_lane

planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp

+22-23
Original file line numberDiff line numberDiff line change
@@ -19,40 +19,39 @@
1919

2020
#include <autoware/universe_utils/geometry/geometry.hpp>
2121

22+
#include <geometry_msgs/msg/pose.hpp>
23+
2224
#include <optional>
23-
#include <vector>
2425

2526
namespace autoware::motion_velocity_planner::out_of_lane
2627
{
27-
28-
/// @brief estimate whether ego can decelerate without breaking the deceleration limit
29-
/// @details assume ego wants to reach the target point at the target velocity
30-
/// @param [in] ego_data ego data
31-
/// @param [in] point target point
32-
/// @param [in] target_vel target_velocity
33-
bool can_decelerate(
34-
const EgoData & ego_data, const TrajectoryPoint & point, const double target_vel);
35-
36-
/// @brief calculate the last pose along the trajectory where ego does not overlap the lane to avoid
28+
/// @brief calculate the last pose along the trajectory where ego does not go out of lane
3729
/// @param [in] ego_data ego data
38-
/// @param [in] decision the input decision (i.e., which lane to avoid and at what speed)
3930
/// @param [in] footprint the ego footprint
40-
/// @param [in] prev_slowdown_point previous slowdown point. If set, ignore deceleration limits
41-
/// @param [in] params parameters
31+
/// @param [in] min_arc_length minimum arc length for the search
32+
/// @param [in] max_arc_length maximum arc length for the search
33+
/// @param [in] precision [m] search precision
4234
/// @return the last pose that is not out of lane (if found)
43-
std::optional<TrajectoryPoint> calculate_last_in_lane_pose(
44-
const EgoData & ego_data, const Slowdown & decision,
45-
const autoware::universe_utils::Polygon2d & footprint,
46-
const std::optional<SlowdownToInsert> & prev_slowdown_point, const PlannerParam & params);
35+
std::optional<geometry_msgs::msg::Pose> calculate_last_in_lane_pose(
36+
const EgoData & ego_data, const autoware::universe_utils::Polygon2d & footprint,
37+
const double min_arc_length, const double max_arc_length, const double precision);
38+
39+
/// @brief calculate the slowdown pose just ahead of a point to avoid
40+
/// @param ego_data ego data (trajectory, velocity, etc)
41+
/// @param point_to_avoid the point to avoid
42+
/// @param footprint the ego footprint
43+
/// @param params parameters
44+
/// @return optional slowdown point to insert in the trajectory
45+
std::optional<geometry_msgs::msg::Pose> calculate_pose_ahead_of_collision(
46+
const EgoData & ego_data, const OutOfLanePoint & point_to_avoid,
47+
const universe_utils::Polygon2d & footprint, const double precision);
4748

4849
/// @brief calculate the slowdown point to insert in the trajectory
4950
/// @param ego_data ego data (trajectory, velocity, etc)
50-
/// @param decisions decision (before which point to stop, what lane to avoid entering, etc)
51-
/// @param prev_slowdown_point previously calculated slowdown point
51+
/// @param out_of_lane_data data about out of lane areas
5252
/// @param params parameters
5353
/// @return optional slowdown point to insert in the trajectory
54-
std::optional<SlowdownToInsert> calculate_slowdown_point(
55-
const EgoData & ego_data, const std::vector<Slowdown> & decisions,
56-
const std::optional<SlowdownToInsert> & prev_slowdown_point, PlannerParam params);
54+
std::optional<geometry_msgs::msg::Pose> calculate_slowdown_point(
55+
const EgoData & ego_data, const OutOfLaneData & out_of_lane_data, PlannerParam params);
5756
} // namespace autoware::motion_velocity_planner::out_of_lane
5857
#endif // CALCULATE_SLOWDOWN_POINTS_HPP_

0 commit comments

Comments
 (0)