Skip to content

Commit d156170

Browse files
maxime-clemzhiwango
authored andcommitted
fix(behavior_path_planner_common): fix dynamic drivable area expansion with few input bound points (autowarefoundation#8136)
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
1 parent ecb33b2 commit d156170

File tree

5 files changed

+63
-16
lines changed

5 files changed

+63
-16
lines changed

planning/behavior_path_planner/autoware_behavior_path_planner/config/drivable_area_expansion.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@
1010
enabled: true
1111
print_runtime: false
1212
max_expansion_distance: 0.0 # [m] maximum distance by which the drivable area can be expended (0.0 means no limit)
13+
min_bound_interval: 0.1 # [m] minimum interval between two consecutive bound points (before expansion)
1314
smoothing:
1415
curvature_average_window: 3 # window size used for smoothing the curvatures using a moving window average
1516
max_bound_rate: 1.0 # [m/m] maximum rate of change of the bound lateral distance over its arc length

planning/behavior_path_planner/autoware_behavior_path_planner/src/behavior_path_planner_node.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -14,8 +14,6 @@
1414

1515
#include "autoware/behavior_path_planner/behavior_path_planner_node.hpp"
1616

17-
#include "autoware/behavior_path_planner_common/marker_utils/utils.hpp"
18-
#include "autoware/behavior_path_planner_common/utils/drivable_area_expansion/static_drivable_area.hpp"
1917
#include "autoware/behavior_path_planner_common/utils/path_utils.hpp"
2018
#include "autoware/motion_utils/trajectory/conversion.hpp"
2119

@@ -909,6 +907,9 @@ SetParametersResult BehaviorPathPlannerNode::onSetParam(
909907
updateParam(
910908
parameters, DrivableAreaExpansionParameters::SMOOTHING_ARC_LENGTH_RANGE_PARAM,
911909
planner_data_->drivable_area_expansion_parameters.arc_length_range);
910+
updateParam(
911+
parameters, DrivableAreaExpansionParameters::MIN_BOUND_INTERVAL,
912+
planner_data_->drivable_area_expansion_parameters.min_bound_interval);
912913
updateParam(
913914
parameters, DrivableAreaExpansionParameters::PRINT_RUNTIME_PARAM,
914915
planner_data_->drivable_area_expansion_parameters.print_runtime);

planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/drivable_area_expansion/parameters.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -58,6 +58,7 @@ struct DrivableAreaExpansionParameters
5858
static constexpr auto SMOOTHING_ARC_LENGTH_RANGE_PARAM =
5959
"dynamic_expansion.smoothing.arc_length_range";
6060
static constexpr auto PRINT_RUNTIME_PARAM = "dynamic_expansion.print_runtime";
61+
static constexpr auto MIN_BOUND_INTERVAL = "dynamic_expansion.min_bound_interval";
6162

6263
// static expansion
6364
double drivable_area_right_bound_offset{};
@@ -80,6 +81,7 @@ struct DrivableAreaExpansionParameters
8081
double resample_interval{};
8182
double arc_length_range{};
8283
double max_reuse_deviation{};
84+
double min_bound_interval{};
8385
bool avoid_dynamic_objects{};
8486
bool print_runtime{};
8587
std::vector<std::string> avoid_linestring_types{};
@@ -119,6 +121,7 @@ struct DrivableAreaExpansionParameters
119121
node.declare_parameter<std::vector<std::string>>(AVOID_LINESTRING_TYPES_PARAM);
120122
avoid_dynamic_objects = node.declare_parameter<bool>(AVOID_DYN_OBJECTS_PARAM);
121123
avoid_linestring_dist = node.declare_parameter<double>(AVOID_LINESTRING_DIST_PARAM);
124+
min_bound_interval = node.declare_parameter<double>(MIN_BOUND_INTERVAL);
122125
print_runtime = node.declare_parameter<bool>(PRINT_RUNTIME_PARAM);
123126

124127
vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(node).getVehicleInfo();

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/drivable_area_expansion/drivable_area_expansion.cpp

+49-5
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2023 TIER IV, Inc.
1+
// Copyright 2023-2024 TIER IV, Inc.
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.
@@ -23,6 +23,8 @@
2323
#include <autoware/motion_utils/resample/resample.hpp>
2424
#include <autoware/motion_utils/trajectory/interpolation.hpp>
2525
#include <autoware/motion_utils/trajectory/trajectory.hpp>
26+
#include <autoware/universe_utils/geometry/boost_geometry.hpp>
27+
#include <autoware/universe_utils/geometry/geometry.hpp>
2628
#include <autoware/universe_utils/system/stop_watch.hpp>
2729
#include <interpolation/linear_interpolation.hpp>
2830

@@ -276,7 +278,13 @@ void expand_bound(
276278
const auto projection = point_to_linestring_projection(bound_p, path_ls);
277279
const auto expansion_ratio = (expansions[idx] + projection.distance) / projection.distance;
278280
const auto & path_p = projection.projected_point;
279-
const auto expanded_p = lerp_point(path_p, bound_p, expansion_ratio);
281+
auto expanded_p = lerp_point(path_p, bound_p, expansion_ratio);
282+
// push the bound again if it got too close to another part of the path
283+
const auto new_projection = point_to_linestring_projection(expanded_p, path_ls);
284+
if (new_projection.distance < projection.distance) {
285+
const auto new_expansion_ratio = (projection.distance) / new_projection.distance;
286+
expanded_p = lerp_point(new_projection.projected_point, expanded_p, new_expansion_ratio);
287+
}
280288
bound[idx].x = expanded_p.x();
281289
bound[idx].y = expanded_p.y();
282290
}
@@ -291,8 +299,8 @@ void expand_bound(
291299
bound[idx - 1], bound[idx], bound[succ_idx - 1], bound[succ_idx]);
292300
if (
293301
intersection &&
294-
autoware::universe_utils::calcDistance2d(*intersection, bound[idx - 1]) < 1e-3 &&
295-
autoware::universe_utils::calcDistance2d(*intersection, bound[idx]) < 1e-3) {
302+
autoware::universe_utils::calcDistance2d(*intersection, bound[idx - 1]) > 1e-3 &&
303+
autoware::universe_utils::calcDistance2d(*intersection, bound[idx]) > 1e-3) {
296304
idx = succ_idx;
297305
is_intersecting = true;
298306
}
@@ -360,6 +368,42 @@ void calculate_expansion_distances(
360368
}
361369
}
362370

371+
void add_bound_point(std::vector<Point> & bound, const Pose & pose, const double min_bound_interval)
372+
{
373+
const auto p = convert_point(pose.position);
374+
PointDistance nearest_projection;
375+
nearest_projection.distance = std::numeric_limits<double>::infinity();
376+
size_t nearest_idx = 0UL;
377+
for (auto i = 0UL; i + 1 < bound.size(); ++i) {
378+
const auto prev_p = convert_point(bound[i]);
379+
const auto next_p = convert_point(bound[i + 1]);
380+
const auto projection = point_to_segment_projection(p, prev_p, next_p);
381+
if (projection.distance < nearest_projection.distance) {
382+
nearest_projection = projection;
383+
nearest_idx = i;
384+
}
385+
}
386+
Point new_point;
387+
new_point.x = nearest_projection.point.x();
388+
new_point.y = nearest_projection.point.y();
389+
new_point.z = bound[nearest_idx].z;
390+
if (
391+
universe_utils::calcDistance2d(new_point, bound[nearest_idx]) > min_bound_interval &&
392+
universe_utils::calcDistance2d(new_point, bound[nearest_idx + 1]) > min_bound_interval) {
393+
bound.insert(bound.begin() + nearest_idx + 1, new_point);
394+
}
395+
}
396+
397+
void add_bound_points(
398+
std::vector<Point> & left_bound, std::vector<Point> & right_bound,
399+
const std::vector<Pose> & path_poses, const double min_bound_interval)
400+
{
401+
for (const auto & p : path_poses) {
402+
add_bound_point(left_bound, p, min_bound_interval);
403+
add_bound_point(right_bound, p, min_bound_interval);
404+
}
405+
}
406+
363407
void expand_drivable_area(
364408
PathWithLaneId & path,
365409
const std::shared_ptr<const autoware::behavior_path_planner::PlannerData> planner_data)
@@ -375,14 +419,14 @@ void expand_drivable_area(
375419
*route_handler.getLaneletMapPtr(), planner_data->self_odometry->pose.pose.position, params);
376420
const auto uncrossable_polygons = create_object_footprints(*planner_data->dynamic_object, params);
377421
const auto preprocessing_ms = stop_watch.toc("preprocessing");
378-
379422
stop_watch.tic("crop");
380423
std::vector<Pose> path_poses = planner_data->drivable_area_expansion_prev_path_poses;
381424
std::vector<double> curvatures = planner_data->drivable_area_expansion_prev_curvatures;
382425

383426
reuse_previous_poses(
384427
path, path_poses, curvatures, planner_data->self_odometry->pose.pose.position, params);
385428
const auto crop_ms = stop_watch.toc("crop");
429+
add_bound_points(path.left_bound, path.right_bound, path_poses, params.min_bound_interval);
386430

387431
stop_watch.tic("curvatures_expansion");
388432
// Only add curvatures for the new points. Curvatures of reused path points are not updated.

planning/behavior_path_planner/autoware_behavior_path_planner_common/test/test_drivable_area_expansion.cpp

+7-9
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2023 TIER IV, Inc.
1+
// Copyright 2023-2024 TIER IV, Inc.
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.
@@ -264,13 +264,11 @@ TEST(DrivableAreaExpansionProjection, expand_drivable_area)
264264
autoware::behavior_path_planner::drivable_area_expansion::expand_drivable_area(
265265
path, std::make_shared<autoware::behavior_path_planner::PlannerData>(planner_data));
266266
// expanded left bound
267-
ASSERT_EQ(path.left_bound.size(), 3ul);
268-
EXPECT_GT(path.left_bound[0].y, 1.0);
269-
EXPECT_GT(path.left_bound[1].y, 1.0);
270-
EXPECT_GT(path.left_bound[2].y, 1.0);
267+
for (const auto & p : path.left_bound) {
268+
EXPECT_GT(p.y, 1.0);
269+
}
271270
// expanded right bound
272-
ASSERT_EQ(path.right_bound.size(), 3ul);
273-
EXPECT_LT(path.right_bound[0].y, -1.0);
274-
EXPECT_LT(path.right_bound[1].y, -1.0);
275-
EXPECT_LT(path.right_bound[2].y, -1.0);
271+
for (const auto & p : path.right_bound) {
272+
EXPECT_LT(p.y, -1.0);
273+
}
276274
}

0 commit comments

Comments
 (0)