@@ -234,14 +234,14 @@ void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugDat
234
234
// calc drivable bound
235
235
auto tmp_path = getPreviousModuleOutput ().path ;
236
236
const auto shorten_lanes = utils::cutOverlappedLanes (tmp_path, data.drivable_lanes );
237
- data.left_bound = toLineString3d ( utils::calcBound (
237
+ data.left_bound = utils::calcBound (
238
238
getPreviousModuleOutput ().path , planner_data_, shorten_lanes,
239
239
parameters_->use_hatched_road_markings , parameters_->use_intersection_areas ,
240
- parameters_->use_freespace_areas , true )) ;
241
- data.right_bound = toLineString3d ( utils::calcBound (
240
+ parameters_->use_freespace_areas , true );
241
+ data.right_bound = utils::calcBound (
242
242
getPreviousModuleOutput ().path , planner_data_, shorten_lanes,
243
243
parameters_->use_hatched_road_markings , parameters_->use_intersection_areas ,
244
- parameters_->use_freespace_areas , false )) ;
244
+ parameters_->use_freespace_areas , false );
245
245
246
246
// reference path
247
247
if (isDrivingSameLane (helper_->getPreviousDrivingLanes (), data.current_lanelets )) {
@@ -294,6 +294,7 @@ void AvoidanceModule::fillAvoidanceTargetObjects(
294
294
using utils::avoidance::filterTargetObjects;
295
295
using utils::avoidance::getTargetLanelets;
296
296
using utils::avoidance::separateObjectsByPath;
297
+ using utils::avoidance::updateRoadShoulderDistance;
297
298
298
299
// Separate dynamic objects based on whether they are inside or outside of the expanded lanelets.
299
300
constexpr double MARGIN = 10.0 ;
@@ -316,6 +317,7 @@ void AvoidanceModule::fillAvoidanceTargetObjects(
316
317
317
318
// Filter out the objects to determine the ones to be avoided.
318
319
filterTargetObjects (objects, data, forward_detection_range, planner_data_, parameters_);
320
+ updateRoadShoulderDistance (data, planner_data_, parameters_);
319
321
320
322
// Calculate the distance needed to safely decelerate the ego vehicle to a stop line.
321
323
const auto & vehicle_width = planner_data_->parameters .vehicle_width ;
@@ -930,10 +932,6 @@ BehaviorModuleOutput AvoidanceModule::plan()
930
932
DrivableAreaInfo current_drivable_area_info;
931
933
// generate drivable lanes
932
934
current_drivable_area_info.drivable_lanes = avoid_data_.drivable_lanes ;
933
- // generate obstacle polygons
934
- current_drivable_area_info.obstacles =
935
- utils::avoidance::generateObstaclePolygonsForDrivableArea (
936
- avoid_data_.target_objects , parameters_, planner_data_->parameters .vehicle_width / 2.0 );
937
935
// expand hatched road markings
938
936
current_drivable_area_info.enable_expanding_hatched_road_markings =
939
937
parameters_->use_hatched_road_markings ;
@@ -942,6 +940,21 @@ BehaviorModuleOutput AvoidanceModule::plan()
942
940
parameters_->use_intersection_areas ;
943
941
// expand freespace areas
944
942
current_drivable_area_info.enable_expanding_freespace_areas = parameters_->use_freespace_areas ;
943
+ // generate obstacle polygons
944
+ if (parameters_->enable_bound_clipping ) {
945
+ ObjectDataArray clip_objects;
946
+ // If avoidance is executed by both behavior and motion, only non-avoidable object will be
947
+ // extracted from the drivable area.
948
+ std::for_each (
949
+ data.target_objects .begin (), data.target_objects .end (), [&](const auto & object) {
950
+ if (!object.is_avoidable ) clip_objects.push_back (object);
951
+ });
952
+ current_drivable_area_info.obstacles =
953
+ utils::avoidance::generateObstaclePolygonsForDrivableArea (
954
+ clip_objects, parameters_, planner_data_->parameters .vehicle_width / 2.0 );
955
+ } else {
956
+ current_drivable_area_info.obstacles .clear ();
957
+ }
945
958
946
959
output.drivable_area_info = utils::combineDrivableAreaInfo (
947
960
current_drivable_area_info, getPreviousModuleOutput ().drivable_area_info );
@@ -1151,8 +1164,8 @@ bool AvoidanceModule::isValidShiftLine(
1151
1164
const size_t end_idx = shift_lines.back ().end_idx ;
1152
1165
1153
1166
const auto path = shifter_for_validate.getReferencePath ();
1154
- const auto left_bound = lanelet::utils::to2D (avoid_data_.left_bound );
1155
- const auto right_bound = lanelet::utils::to2D (avoid_data_.right_bound );
1167
+ const auto left_bound = lanelet::utils::to2D (toLineString3d ( avoid_data_.left_bound ) );
1168
+ const auto right_bound = lanelet::utils::to2D (toLineString3d ( avoid_data_.right_bound ) );
1156
1169
for (size_t i = start_idx; i <= end_idx; ++i) {
1157
1170
const auto p = getPoint (path.points .at (i));
1158
1171
lanelet::BasicPoint2d basic_point{p.x , p.y };
0 commit comments