Skip to content

Commit f8c8bb1

Browse files
authored
Merge branch 'beta/v0.29.0-1' into fix/overwrite_invalid_detection_result/v0.29.0-1
2 parents 47e2931 + e89815f commit f8c8bb1

File tree

8 files changed

+20176
-93
lines changed

8 files changed

+20176
-93
lines changed

planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/CMakeLists.txt

+10
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,16 @@ target_link_libraries(${PROJECT_NAME}
2828

2929
ament_auto_package(INSTALL_TO_SHARE config)
3030

31+
if(BUILD_TESTING)
32+
find_package(ament_lint_auto REQUIRED)
33+
ament_lint_auto_find_test_dependencies()
34+
file(GLOB_RECURSE TEST_SOURCES test/*.cpp)
35+
ament_add_ros_isolated_gtest(test_${PROJECT_NAME}
36+
${TEST_SOURCES}
37+
)
38+
target_link_libraries(test_${PROJECT_NAME} ${PROJECT_NAME})
39+
endif()
40+
3141
install(PROGRAMS
3242
scripts/ttc.py
3343
DESTINATION lib/${PROJECT_NAME}

planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/package.xml

+2
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@
2424
<depend>autoware_planning_msgs</depend>
2525
<depend>autoware_route_handler</depend>
2626
<depend>autoware_rtc_interface</depend>
27+
<depend>autoware_test_utils</depend>
2728
<depend>autoware_universe_utils</depend>
2829
<depend>autoware_vehicle_info_utils</depend>
2930
<depend>fmt</depend>
@@ -39,6 +40,7 @@
3940
<depend>tier4_planning_msgs</depend>
4041
<depend>visualization_msgs</depend>
4142

43+
<test_depend>ament_cmake_ros</test_depend>
4244
<test_depend>ament_lint_auto</test_depend>
4345
<test_depend>autoware_lint_common</test_depend>
4446

planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -590,7 +590,8 @@ class IntersectionModule : public SceneModuleInterface
590590
* @brief generate discretized detection lane linestring.
591591
*/
592592
std::vector<lanelet::ConstLineString3d> generateDetectionLaneDivisions(
593-
lanelet::ConstLanelets detection_lanelets,
593+
const lanelet::ConstLanelets & occlusion_detection_lanelets,
594+
const lanelet::ConstLanelets & conflicting_detection_lanelets,
594595
const lanelet::routing::RoutingGraphPtr routing_graph_ptr, const double resolution) const;
595596
/** @} */
596597

planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp

+88-21
Original file line numberDiff line numberDiff line change
@@ -266,8 +266,8 @@ Result<IntersectionModule::BasicData, InternalError> IntersectionModule::prepare
266266

267267
if (!occlusion_attention_divisions_) {
268268
occlusion_attention_divisions_ = generateDetectionLaneDivisions(
269-
intersection_lanelets.occlusion_attention(), routing_graph_ptr,
270-
planner_data_->occupancy_grid->info.resolution);
269+
intersection_lanelets.occlusion_attention(), intersection_lanelets.attention_non_preceding(),
270+
routing_graph_ptr, planner_data_->occupancy_grid->info.resolution);
271271
}
272272

273273
if (has_traffic_light_) {
@@ -577,6 +577,73 @@ std::optional<IntersectionStopLines> IntersectionModule::generateIntersectionSto
577577
return intersection_stoplines;
578578
}
579579

580+
static std::vector<std::deque<lanelet::ConstLanelet>> getPrecedingLaneletsUptoIntersectionRecursive(
581+
const lanelet::routing::RoutingGraphPtr & graph, const lanelet::ConstLanelet & lanelet,
582+
const double length, const lanelet::ConstLanelets & exclude_lanelets)
583+
{
584+
std::vector<std::deque<lanelet::ConstLanelet>> preceding_lanelet_sequences;
585+
586+
const auto prev_lanelets = graph->previous(lanelet);
587+
const double lanelet_length = lanelet::utils::getLaneletLength3d(lanelet);
588+
589+
// end condition of the recursive function
590+
if (prev_lanelets.empty() || lanelet_length >= length) {
591+
preceding_lanelet_sequences.push_back({lanelet});
592+
return preceding_lanelet_sequences;
593+
}
594+
595+
for (const auto & prev_lanelet : prev_lanelets) {
596+
if (lanelet::utils::contains(exclude_lanelets, prev_lanelet)) {
597+
// if prev_lanelet is included in exclude_lanelets,
598+
// remove prev_lanelet from preceding_lanelet_sequences
599+
continue;
600+
}
601+
if (const std::string turn_direction = prev_lanelet.attributeOr("turn_direction", "else");
602+
turn_direction == "left" || turn_direction == "right") {
603+
continue;
604+
}
605+
606+
// get lanelet sequence after prev_lanelet
607+
auto tmp_lanelet_sequences = getPrecedingLaneletsUptoIntersectionRecursive(
608+
graph, prev_lanelet, length - lanelet_length, exclude_lanelets);
609+
for (auto & tmp_lanelet_sequence : tmp_lanelet_sequences) {
610+
tmp_lanelet_sequence.push_back(lanelet);
611+
preceding_lanelet_sequences.push_back(tmp_lanelet_sequence);
612+
}
613+
}
614+
615+
if (preceding_lanelet_sequences.empty()) {
616+
preceding_lanelet_sequences.push_back({lanelet});
617+
}
618+
return preceding_lanelet_sequences;
619+
}
620+
621+
static std::vector<lanelet::ConstLanelets> getPrecedingLaneletsUptoIntersection(
622+
const lanelet::routing::RoutingGraphPtr & graph, const lanelet::ConstLanelet & lanelet,
623+
const double length, const lanelet::ConstLanelets & exclude_lanelets)
624+
{
625+
std::vector<lanelet::ConstLanelets> lanelet_sequences_vec;
626+
const auto prev_lanelets = graph->previous(lanelet);
627+
for (const auto & prev_lanelet : prev_lanelets) {
628+
if (lanelet::utils::contains(exclude_lanelets, prev_lanelet)) {
629+
// if prev_lanelet is included in exclude_lanelets,
630+
// remove prev_lanelet from preceding_lanelet_sequences
631+
continue;
632+
}
633+
if (const std::string turn_direction = prev_lanelet.attributeOr("turn_direction", "else");
634+
turn_direction == "left" || turn_direction == "right") {
635+
continue;
636+
}
637+
// convert deque into vector
638+
const auto lanelet_sequences_deq =
639+
getPrecedingLaneletsUptoIntersectionRecursive(graph, prev_lanelet, length, exclude_lanelets);
640+
for (const auto & lanelet_sequence : lanelet_sequences_deq) {
641+
lanelet_sequences_vec.emplace_back(lanelet_sequence.begin(), lanelet_sequence.end());
642+
}
643+
}
644+
return lanelet_sequences_vec;
645+
}
646+
580647
IntersectionLanelets IntersectionModule::generateObjectiveLanelets(
581648
lanelet::LaneletMapConstPtr lanelet_map_ptr, lanelet::routing::RoutingGraphPtr routing_graph_ptr,
582649
const lanelet::ConstLanelet assigned_lanelet) const
@@ -706,8 +773,8 @@ IntersectionLanelets IntersectionModule::generateObjectiveLanelets(
706773
if (inserted.second) occlusion_detection_and_preceding_lanelets.push_back(ll);
707774
// get preceding lanelets without ego_lanelets
708775
// to prevent the detection area from including the ego lanes and its' preceding lanes.
709-
const auto lanelet_sequences = lanelet::utils::query::getPrecedingLaneletSequences(
710-
routing_graph_ptr, ll, length, ego_lanelets);
776+
const auto lanelet_sequences =
777+
getPrecedingLaneletsUptoIntersection(routing_graph_ptr, ll, length, ego_lanelets);
711778
for (const auto & ls : lanelet_sequences) {
712779
for (const auto & l : ls) {
713780
const auto & inserted = detection_ids.insert(l.id());
@@ -716,17 +783,10 @@ IntersectionLanelets IntersectionModule::generateObjectiveLanelets(
716783
}
717784
}
718785
}
719-
lanelet::ConstLanelets occlusion_detection_and_preceding_lanelets_wo_turn_direction;
720-
for (const auto & ll : occlusion_detection_and_preceding_lanelets) {
721-
const std::string turn_direction = ll.attributeOr("turn_direction", "else");
722-
if (turn_direction == "left" || turn_direction == "right") {
723-
continue;
724-
}
725-
occlusion_detection_and_preceding_lanelets_wo_turn_direction.push_back(ll);
726-
}
727786

728787
auto [attention_lanelets, original_attention_lanelet_sequences] =
729-
util::mergeLaneletsByTopologicalSort(detection_and_preceding_lanelets, routing_graph_ptr);
788+
util::mergeLaneletsByTopologicalSort(
789+
detection_and_preceding_lanelets, detection_lanelets, routing_graph_ptr);
730790

731791
IntersectionLanelets result;
732792
result.attention_ = std::move(attention_lanelets);
@@ -764,8 +824,7 @@ IntersectionLanelets IntersectionModule::generateObjectiveLanelets(
764824
// NOTE: occlusion_attention is not inverted here
765825
// TODO(Mamoru Sobue): apply mergeLaneletsByTopologicalSort for occlusion lanelets as well and
766826
// then trim part of them based on curvature threshold
767-
result.occlusion_attention_ =
768-
std::move(occlusion_detection_and_preceding_lanelets_wo_turn_direction);
827+
result.occlusion_attention_ = std::move(occlusion_detection_and_preceding_lanelets);
769828

770829
// NOTE: to properly update(), each element in conflicting_/conflicting_area_,
771830
// attention_non_preceding_/attention_non_preceding_area_ need to be matched
@@ -851,7 +910,8 @@ std::optional<PathLanelets> IntersectionModule::generatePathLanelets(
851910
}
852911

853912
std::vector<lanelet::ConstLineString3d> IntersectionModule::generateDetectionLaneDivisions(
854-
lanelet::ConstLanelets detection_lanelets_all,
913+
const lanelet::ConstLanelets & occlusion_detection_lanelets,
914+
const lanelet::ConstLanelets & conflicting_detection_lanelets,
855915
const lanelet::routing::RoutingGraphPtr routing_graph_ptr, const double resolution) const
856916
{
857917
const double curvature_threshold =
@@ -861,9 +921,9 @@ std::vector<lanelet::ConstLineString3d> IntersectionModule::generateDetectionLan
861921

862922
using lanelet::utils::getCenterlineWithOffset;
863923

864-
// (0) remove left/right lanelet
924+
// (0) remove curved
865925
lanelet::ConstLanelets detection_lanelets;
866-
for (const auto & detection_lanelet : detection_lanelets_all) {
926+
for (const auto & detection_lanelet : occlusion_detection_lanelets) {
867927
// TODO(Mamoru Sobue): instead of ignoring, only trim straight part of lanelet
868928
const auto fine_centerline =
869929
lanelet::utils::generateFineCenterline(detection_lanelet, curvature_calculation_ds);
@@ -874,9 +934,17 @@ std::vector<lanelet::ConstLineString3d> IntersectionModule::generateDetectionLan
874934
detection_lanelets.push_back(detection_lanelet);
875935
}
876936

937+
std::vector<lanelet::ConstLineString3d> detection_divisions;
938+
if (detection_lanelets.empty()) {
939+
// NOTE(soblin): due to the above filtering detection_lanelets may be empty or do not contain
940+
// conflicting_detection_lanelets
941+
// OK to return empty detction_divsions
942+
return detection_divisions;
943+
}
944+
877945
// (1) tsort detection_lanelets
878-
const auto [merged_detection_lanelets, originals] =
879-
util::mergeLaneletsByTopologicalSort(detection_lanelets, routing_graph_ptr);
946+
const auto [merged_detection_lanelets, originals] = util::mergeLaneletsByTopologicalSort(
947+
detection_lanelets, conflicting_detection_lanelets, routing_graph_ptr);
880948

881949
// (2) merge each branch to one lanelet
882950
// NOTE: somehow bg::area() for merged lanelet does not work, so calculate it here
@@ -892,7 +960,6 @@ std::vector<lanelet::ConstLineString3d> IntersectionModule::generateDetectionLan
892960
}
893961

894962
// (3) discretize each merged lanelet
895-
std::vector<lanelet::ConstLineString3d> detection_divisions;
896963
for (const auto & [merged_lanelet, area] : merged_lanelet_with_area) {
897964
const double length = bg::length(merged_lanelet.centerline());
898965
const double width = area / length;

0 commit comments

Comments
 (0)