|
21 | 21 | #include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp"
|
22 | 22 | #include "behavior_path_planner_common/utils/path_safety_checker/safety_check.hpp"
|
23 | 23 | #include "behavior_path_planner_common/utils/path_utils.hpp"
|
| 24 | +#include "behavior_path_planner_common/utils/traffic_light_utils.hpp" |
24 | 25 | #include "behavior_path_planner_common/utils/utils.hpp"
|
25 | 26 |
|
26 | 27 | #include <lanelet2_extension/utility/message_conversion.hpp>
|
|
32 | 33 | #include "tier4_planning_msgs/msg/detail/avoidance_debug_msg_array__struct.hpp"
|
33 | 34 | #include <tier4_planning_msgs/msg/detail/avoidance_debug_factor__struct.hpp>
|
34 | 35 |
|
35 |
| -#include <boost/geometry/algorithms/centroid.hpp> |
36 |
| - |
37 | 36 | #include <algorithm>
|
38 | 37 | #include <limits>
|
39 | 38 | #include <memory>
|
@@ -223,25 +222,37 @@ void AvoidanceModule::fillFundamentalData(AvoidancePlanningData & data, DebugDat
|
223 | 222 | utils::avoidance::getExtendLanes(data.current_lanelets, getEgoPose(), planner_data_);
|
224 | 223 |
|
225 | 224 | // expand drivable lanes
|
226 |
| - const auto has_shift_point = !path_shifter_.getShiftLines().empty(); |
227 |
| - const auto in_avoidance_maneuver = has_shift_point || helper_->isShifted(); |
| 225 | + const auto is_within_current_lane = |
| 226 | + utils::avoidance::isWithinLanes(data.current_lanelets, planner_data_); |
228 | 227 | std::for_each(
|
229 | 228 | data.current_lanelets.begin(), data.current_lanelets.end(), [&](const auto & lanelet) {
|
230 |
| - data.drivable_lanes.push_back(utils::avoidance::generateExpandDrivableLanes( |
231 |
| - lanelet, planner_data_, parameters_, in_avoidance_maneuver)); |
| 229 | + const auto next_lanes = planner_data_->route_handler->getNextLanelets(lanelet); |
| 230 | + const auto is_stop_signal = |
| 231 | + utils::traffic_light::isTrafficSignalStop(next_lanes, planner_data_); |
| 232 | + const auto limit_drivable_lane = is_stop_signal && is_within_current_lane; |
| 233 | + if (limit_drivable_lane) { |
| 234 | + data.limit_drivable_lane = true; |
| 235 | + data.drivable_lanes.emplace_back(lanelet); |
| 236 | + } else { |
| 237 | + data.drivable_lanes.push_back( |
| 238 | + utils::avoidance::generateExpandDrivableLanes(lanelet, planner_data_, parameters_)); |
| 239 | + } |
232 | 240 | });
|
233 | 241 |
|
234 | 242 | // calc drivable bound
|
235 | 243 | auto tmp_path = getPreviousModuleOutput().path;
|
| 244 | + const auto use_hatched_road_markings = |
| 245 | + parameters_->use_hatched_road_markings && !data.limit_drivable_lane; |
| 246 | + const auto use_intersection_areas = |
| 247 | + parameters_->use_intersection_areas && !data.limit_drivable_lane; |
| 248 | + const auto use_freespace_areas = parameters_->use_freespace_areas && !data.limit_drivable_lane; |
236 | 249 | const auto shorten_lanes = utils::cutOverlappedLanes(tmp_path, data.drivable_lanes);
|
237 | 250 | data.left_bound = utils::calcBound(
|
238 |
| - getPreviousModuleOutput().path, planner_data_, shorten_lanes, |
239 |
| - parameters_->use_hatched_road_markings, parameters_->use_intersection_areas, |
240 |
| - parameters_->use_freespace_areas, true); |
| 251 | + getPreviousModuleOutput().path, planner_data_, shorten_lanes, use_hatched_road_markings, |
| 252 | + use_intersection_areas, use_freespace_areas, true); |
241 | 253 | data.right_bound = utils::calcBound(
|
242 |
| - getPreviousModuleOutput().path, planner_data_, shorten_lanes, |
243 |
| - parameters_->use_hatched_road_markings, parameters_->use_intersection_areas, |
244 |
| - parameters_->use_freespace_areas, false); |
| 254 | + getPreviousModuleOutput().path, planner_data_, shorten_lanes, use_hatched_road_markings, |
| 255 | + use_intersection_areas, use_freespace_areas, false); |
245 | 256 |
|
246 | 257 | // reference path
|
247 | 258 | if (isDrivingSameLane(helper_->getPreviousDrivingLanes(), data.current_lanelets)) {
|
@@ -942,12 +953,13 @@ BehaviorModuleOutput AvoidanceModule::plan()
|
942 | 953 | current_drivable_area_info.drivable_lanes = avoid_data_.drivable_lanes;
|
943 | 954 | // expand hatched road markings
|
944 | 955 | current_drivable_area_info.enable_expanding_hatched_road_markings =
|
945 |
| - parameters_->use_hatched_road_markings; |
| 956 | + parameters_->use_hatched_road_markings && !data.limit_drivable_lane; |
946 | 957 | // expand intersection areas
|
947 | 958 | current_drivable_area_info.enable_expanding_intersection_areas =
|
948 |
| - parameters_->use_intersection_areas; |
| 959 | + parameters_->use_intersection_areas && !data.limit_drivable_lane; |
949 | 960 | // expand freespace areas
|
950 |
| - current_drivable_area_info.enable_expanding_freespace_areas = parameters_->use_freespace_areas; |
| 961 | + current_drivable_area_info.enable_expanding_freespace_areas = |
| 962 | + parameters_->use_freespace_areas && !data.limit_drivable_lane; |
951 | 963 | // generate obstacle polygons
|
952 | 964 | if (parameters_->enable_bound_clipping) {
|
953 | 965 | ObjectDataArray clip_objects;
|
|
0 commit comments