Skip to content

Commit 7778982

Browse files
authored
feat(drivable area expansion): do not over expand beyond the desired width (autowarefoundation#5640)
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
1 parent b3cd3fc commit 7778982

File tree

8 files changed

+233
-102
lines changed

8 files changed

+233
-102
lines changed

planning/behavior_path_planner/config/drivable_area_expansion.param.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@
1313
smoothing:
1414
curvature_average_window: 3 # window size used for smoothing the curvatures using a moving window average
1515
max_bound_rate: 1.0 # [m/m] maximum rate of change of the bound lateral distance over its arc length
16-
extra_arc_length: 2.0 # [m] extra arc length where an expansion distance is initially applied
16+
arc_length_range: 2.0 # [m] arc length range where an expansion distance is initially applied
1717
ego:
1818
extra_wheelbase: 0.0 # [m] extra length to add to the wheelbase
1919
extra_front_overhang: 0.5 # [m] extra length to add to the front overhang

planning/behavior_path_planner/src/behavior_path_planner_node.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -929,8 +929,8 @@ SetParametersResult BehaviorPathPlannerNode::onSetParam(
929929
parameters, DrivableAreaExpansionParameters::SMOOTHING_MAX_BOUND_RATE_PARAM,
930930
planner_data_->drivable_area_expansion_parameters.max_bound_rate);
931931
updateParam(
932-
parameters, DrivableAreaExpansionParameters::SMOOTHING_EXTRA_ARC_LENGTH_PARAM,
933-
planner_data_->drivable_area_expansion_parameters.extra_arc_length);
932+
parameters, DrivableAreaExpansionParameters::SMOOTHING_ARC_LENGTH_RANGE_PARAM,
933+
planner_data_->drivable_area_expansion_parameters.arc_length_range);
934934
updateParam(
935935
parameters, DrivableAreaExpansionParameters::PRINT_RUNTIME_PARAM,
936936
planner_data_->drivable_area_expansion_parameters.print_runtime);

planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/drivable_area_expansion/drivable_area_expansion.hpp

+44-6
Original file line numberDiff line numberDiff line change
@@ -35,14 +35,14 @@ void expand_drivable_area(
3535
PathWithLaneId & path,
3636
const std::shared_ptr<const behavior_path_planner::PlannerData> planner_data);
3737

38-
/// @brief prepare path poses and try to reuse their previously calculated curvatures
38+
/// @brief try to reuse the previous path poses and their previously calculated curvatures
3939
/// @details poses are reused if they do not deviate too much from the current path
4040
/// @param [in] path input path
4141
/// @param [inout] prev_poses previous poses to reuse
4242
/// @param [inout] prev_curvatures previous curvatures to reuse
4343
/// @param [in] ego_point current ego point
4444
/// @param [in] params parameters for reuse criteria and resampling interval
45-
void update_path_poses_and_previous_curvatures(
45+
void reuse_previous_poses(
4646
const PathWithLaneId & path, std::vector<Pose> & prev_poses,
4747
std::vector<double> & prev_curvatures, const Point & ego_point,
4848
const DrivableAreaExpansionParameters & params);
@@ -57,6 +57,36 @@ void update_path_poses_and_previous_curvatures(
5757
double calculate_minimum_lane_width(
5858
const double curvature_radius, const DrivableAreaExpansionParameters & params);
5959

60+
/// @brief calculate mappings between path poses and the given drivable area bound
61+
/// @param [inout] expansion expansion data to update with the mapping
62+
/// @param [in] path_poses path poses
63+
/// @param [in] bound drivable area bound
64+
/// @param [in] Side left or right side
65+
void calculate_bound_index_mappings(
66+
Expansion & expansion, const std::vector<Pose> & path_poses, const std::vector<Point> & bound,
67+
const Side side);
68+
69+
/// @brief apply expansion distances to all bound points within the given arc length range
70+
/// @param [inout] expansion expansion data to update
71+
/// @param [in] bound drivable area bound
72+
/// @param [in] arc_length_range [m] arc length range where the expansion distances are also applied
73+
/// @param [in] Side left or right side
74+
void apply_arc_length_range_smoothing(
75+
Expansion & expansion, const std::vector<Point> & bound, const double arc_length_range,
76+
const Side side);
77+
78+
/// @brief calculate minimum lane widths and mappings between path and and drivable area bounds
79+
/// @param [in] path_poses path poses
80+
/// @param [in] left_bound left drivable area bound
81+
/// @param [in] right_bound right drivable area bound
82+
/// @param [in] curvatures curvatures at each path point
83+
/// @param [in] params parameters with the vehicle dimensions used to calculate the min lane width
84+
/// @return expansion data (path->bound mappings, min lane widths, ...)
85+
Expansion calculate_expansion(
86+
const std::vector<Pose> & path_poses, const std::vector<Point> & left_bound,
87+
const std::vector<Point> & right_bound, const std::vector<double> & curvatures,
88+
const DrivableAreaExpansionParameters & params);
89+
6090
/// @brief smooth the bound by applying a limit on its rate of change
6191
/// @details rate of change is the lateral distance from the path over the arc length along the path
6292
/// @param [inout] bound_distances bound distances (lateral distance from the path)
@@ -66,16 +96,16 @@ void apply_bound_change_rate_limit(
6696
std::vector<double> & distances, const std::vector<Point> & bound, const double max_rate);
6797

6898
/// @brief calculate the maximum distance by which a bound can be expanded
69-
/// @param [in] path_poses input path
7099
/// @param [in] bound bound points
71100
/// @param [in] uncrossable_segments segments that limit the bound expansion, indexed in a Rtree
72101
/// @param [in] uncrossable_polygons polygons that limit the bound expansion
73102
/// @param [in] params parameters with the buffer distance to keep with lines,
74103
/// and the static maximum expansion distance
104+
/// @param [in] Side left or right side
75105
std::vector<double> calculate_maximum_distance(
76-
const std::vector<Pose> & path_poses, const std::vector<Point> bound,
77-
const SegmentRtree & uncrossable_lines, const std::vector<Polygon2d> & uncrossable_polygons,
78-
const DrivableAreaExpansionParameters & params);
106+
const std::vector<Point> & bound, const SegmentRtree & uncrossable_lines,
107+
const std::vector<Polygon2d> & uncrossable_polygons,
108+
const DrivableAreaExpansionParameters & params, const Side side);
79109

80110
/// @brief expand a bound by the given lateral distances away from the path
81111
/// @param [inout] bound bound points to expand
@@ -85,6 +115,14 @@ void expand_bound(
85115
std::vector<Point> & bound, const std::vector<Pose> & path_poses,
86116
const std::vector<double> & distances);
87117

118+
/// @brief calculate the expansion distances of the left and right drivable area bounds
119+
/// @param [inout] expansion expansion data to be updated with the left/right expansion distances
120+
/// @param [in] max_left_expansions maximum left expansion distances
121+
/// @param [in] max_right_expansions maximum right expansion distances
122+
void calculate_expansion_distances(
123+
Expansion & expansion, const std::vector<double> & max_left_expansions,
124+
const std::vector<double> & max_right_expansions);
125+
88126
/// @brief calculate smoothed curvatures
89127
/// @details smoothing is done using a moving average
90128
/// @param [in] poses input poses used to calculate the curvatures

planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/drivable_area_expansion/parameters.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -55,8 +55,8 @@ struct DrivableAreaExpansionParameters
5555
"dynamic_expansion.smoothing.curvature_average_window";
5656
static constexpr auto SMOOTHING_MAX_BOUND_RATE_PARAM =
5757
"dynamic_expansion.smoothing.max_bound_rate";
58-
static constexpr auto SMOOTHING_EXTRA_ARC_LENGTH_PARAM =
59-
"dynamic_expansion.smoothing.extra_arc_length";
58+
static constexpr auto SMOOTHING_ARC_LENGTH_RANGE_PARAM =
59+
"dynamic_expansion.smoothing.arc_length_range";
6060
static constexpr auto PRINT_RUNTIME_PARAM = "dynamic_expansion.print_runtime";
6161

6262
// static expansion
@@ -78,7 +78,7 @@ struct DrivableAreaExpansionParameters
7878
double max_expansion_distance{};
7979
double max_path_arc_length{};
8080
double resample_interval{};
81-
double extra_arc_length{};
81+
double arc_length_range{};
8282
double max_reuse_deviation{};
8383
bool avoid_dynamic_objects{};
8484
bool print_runtime{};
@@ -103,7 +103,7 @@ struct DrivableAreaExpansionParameters
103103
extra_width = node.declare_parameter<double>(EGO_EXTRA_WIDTH);
104104
curvature_average_window = node.declare_parameter<int>(SMOOTHING_CURVATURE_WINDOW_PARAM);
105105
max_bound_rate = node.declare_parameter<double>(SMOOTHING_MAX_BOUND_RATE_PARAM);
106-
extra_arc_length = node.declare_parameter<double>(SMOOTHING_EXTRA_ARC_LENGTH_PARAM);
106+
arc_length_range = node.declare_parameter<double>(SMOOTHING_ARC_LENGTH_RANGE_PARAM);
107107
max_path_arc_length = node.declare_parameter<double>(MAX_PATH_ARC_LENGTH_PARAM);
108108
resample_interval = node.declare_parameter<double>(RESAMPLE_INTERVAL_PARAM);
109109
max_reuse_deviation = node.declare_parameter<double>(MAX_REUSE_DEVIATION_PARAM);

planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/drivable_area_expansion/path_projection.hpp

+5-13
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,6 @@
2626
namespace drivable_area_expansion
2727
{
2828
/// @brief project a point to a segment
29-
/// @details the distance is signed based on the side of the point: left=positive, right=negative
3029
/// @param p point to project on the segment
3130
/// @param p1 first segment point
3231
/// @param p2 second segment point
@@ -37,22 +36,18 @@ inline PointDistance point_to_segment_projection(
3736
const Point2d p2_vec = {p2.x() - p1.x(), p2.y() - p1.y()};
3837
const Point2d p_vec = {p.x() - p1.x(), p.y() - p1.y()};
3938

40-
const auto cross = p2_vec.x() * p_vec.y() - p2_vec.y() * p_vec.x();
41-
const auto dist_sign = cross < 0.0 ? -1.0 : 1.0;
42-
4339
const auto c1 = boost::geometry::dot_product(p_vec, p2_vec);
44-
if (c1 <= 0) return {p1, boost::geometry::distance(p, p1) * dist_sign};
40+
if (c1 <= 0) return {p1, boost::geometry::distance(p, p1)};
4541

4642
const auto c2 = boost::geometry::dot_product(p2_vec, p2_vec);
47-
if (c2 <= c1) return {p2, boost::geometry::distance(p, p2) * dist_sign};
43+
if (c2 <= c1) return {p2, boost::geometry::distance(p, p2)};
4844

4945
const auto projection = p1 + (p2_vec * c1 / c2);
5046
const auto projection_point = Point2d{projection.x(), projection.y()};
51-
return {projection_point, boost::geometry::distance(p, projection_point) * dist_sign};
47+
return {projection_point, boost::geometry::distance(p, projection_point)};
5248
}
5349

5450
/// @brief project a point to a line
55-
/// @details the distance is signed based on the side of the point: left=positive, right=negative
5651
/// @param p point to project on the line
5752
/// @param p1 first line point
5853
/// @param p2 second line point
@@ -63,14 +58,11 @@ inline PointDistance point_to_line_projection(
6358
const Point2d p2_vec = {p2.x() - p1.x(), p2.y() - p1.y()};
6459
const Point2d p_vec = {p.x() - p1.x(), p.y() - p1.y()};
6560

66-
const auto cross = p2_vec.x() * p_vec.y() - p2_vec.y() * p_vec.x();
67-
const auto dist_sign = cross < 0.0 ? -1.0 : 1.0;
68-
6961
const auto c1 = boost::geometry::dot_product(p_vec, p2_vec);
7062
const auto c2 = boost::geometry::dot_product(p2_vec, p2_vec);
7163
const auto projection = p1 + (p2_vec * c1 / c2);
7264
const auto projection_point = Point2d{projection.x(), projection.y()};
73-
return {projection_point, boost::geometry::distance(p, projection_point) * dist_sign};
65+
return {projection_point, boost::geometry::distance(p, projection_point)};
7466
}
7567

7668
/// @brief project a point to a linestring
@@ -84,7 +76,7 @@ inline Projection point_to_linestring_projection(const Point2d & p, const LineSt
8476
auto arc_length = 0.0;
8577
for (auto ls_it = ls.begin(); std::next(ls_it) != ls.end(); ++ls_it) {
8678
const auto pd = point_to_segment_projection(p, *ls_it, *(ls_it + 1));
87-
if (std::abs(pd.distance) < std::abs(closest.distance)) {
79+
if (pd.distance < closest.distance) {
8880
closest.projected_point = pd.point;
8981
closest.distance = pd.distance;
9082
closest.arc_length = arc_length + boost::geometry::distance(*ls_it, pd.point);

planning/behavior_path_planner_common/include/behavior_path_planner_common/utils/drivable_area_expansion/types.hpp

+20-6
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,9 @@
2424

2525
#include <boost/geometry/index/rtree.hpp>
2626

27+
#include <optional>
28+
#include <vector>
29+
2730
namespace drivable_area_expansion
2831
{
2932
using autoware_auto_perception_msgs::msg::PredictedObjects;
@@ -45,16 +48,27 @@ using SegmentRtree = boost::geometry::index::rtree<Segment2d, boost::geometry::i
4548

4649
struct PointDistance
4750
{
48-
Point2d point;
49-
double distance{0.0};
51+
Point2d point{};
52+
double distance{};
5053
};
5154
struct Projection
5255
{
53-
Point2d projected_point;
54-
double distance{0.0};
55-
double arc_length{0.0};
56+
Point2d projected_point{};
57+
double distance{};
58+
double arc_length{};
5659
};
5760
enum Side { LEFT, RIGHT };
58-
61+
struct Expansion
62+
{
63+
// mappings from bound index
64+
std::vector<double> left_distances;
65+
std::vector<double> right_distances;
66+
// mappings from path index
67+
std::vector<size_t> left_bound_indexes;
68+
std::vector<PointDistance> left_projections;
69+
std::vector<size_t> right_bound_indexes;
70+
std::vector<PointDistance> right_projections;
71+
std::vector<double> min_lane_widths;
72+
};
5973
} // namespace drivable_area_expansion
6074
#endif // BEHAVIOR_PATH_PLANNER_COMMON__UTILS__DRIVABLE_AREA_EXPANSION__TYPES_HPP_

0 commit comments

Comments
 (0)