Skip to content

Commit 8512daf

Browse files
committed
refactor(intersection): divide source files and modifyPathVelocity (autowarefoundation#6134)
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent 6903e5b commit 8512daf

18 files changed

+3792
-3064
lines changed

planning/behavior_velocity_intersection_module/CMakeLists.txt

+7-2
Original file line numberDiff line numberDiff line change
@@ -8,11 +8,16 @@ pluginlib_export_plugin_description_file(behavior_velocity_planner plugins.xml)
88
find_package(OpenCV REQUIRED)
99

1010
ament_auto_add_library(${PROJECT_NAME} SHARED
11-
src/debug.cpp
1211
src/manager.cpp
12+
src/util.cpp
1313
src/scene_intersection.cpp
14+
src/intersection_lanelets.cpp
15+
src/scene_intersection_prepare_data.cpp
16+
src/scene_intersection_stuck.cpp
17+
src/scene_intersection_occlusion.cpp
18+
src/scene_intersection_collision.cpp
1419
src/scene_merge_from_private_road.cpp
15-
src/util.cpp
20+
src/debug.cpp
1621
)
1722

1823
target_link_libraries(${PROJECT_NAME}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,203 @@
1+
// Copyright 2024 Tier IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef DECISION_RESULT_HPP_
16+
#define DECISION_RESULT_HPP_
17+
18+
#include <optional>
19+
#include <string>
20+
#include <variant>
21+
22+
namespace behavior_velocity_planner::intersection
23+
{
24+
25+
/**
26+
* @struct
27+
* @brief Internal error or ego already passed pass_judge_line
28+
*/
29+
struct Indecisive
30+
{
31+
std::string error;
32+
};
33+
34+
/**
35+
* @struct
36+
* @brief detected stuck vehicle
37+
*/
38+
struct StuckStop
39+
{
40+
size_t closest_idx{0};
41+
size_t stuck_stopline_idx{0};
42+
std::optional<size_t> occlusion_stopline_idx{std::nullopt};
43+
};
44+
45+
/**
46+
* @struct
47+
* @brief yielded by vehicle on the attention area
48+
*/
49+
struct YieldStuckStop
50+
{
51+
size_t closest_idx{0};
52+
size_t stuck_stopline_idx{0};
53+
};
54+
55+
/**
56+
* @struct
57+
* @brief only collision is detected
58+
*/
59+
struct NonOccludedCollisionStop
60+
{
61+
size_t closest_idx{0};
62+
size_t collision_stopline_idx{0};
63+
size_t occlusion_stopline_idx{0};
64+
};
65+
66+
/**
67+
* @struct
68+
* @brief occlusion is detected so ego needs to stop at the default stop line position
69+
*/
70+
struct FirstWaitBeforeOcclusion
71+
{
72+
bool is_actually_occlusion_cleared{false};
73+
size_t closest_idx{0};
74+
size_t first_stopline_idx{0};
75+
size_t occlusion_stopline_idx{0};
76+
};
77+
78+
/**
79+
* @struct
80+
* @brief ego is approaching the boundary of attention area in the presence of traffic light
81+
*/
82+
struct PeekingTowardOcclusion
83+
{
84+
//! if intersection_occlusion is disapproved externally through RTC, it indicates
85+
//! "is_forcefully_occluded"
86+
bool is_actually_occlusion_cleared{false};
87+
bool temporal_stop_before_attention_required{false};
88+
size_t closest_idx{0};
89+
size_t collision_stopline_idx{0};
90+
size_t first_attention_stopline_idx{0};
91+
size_t occlusion_stopline_idx{0};
92+
//! if null, it is dynamic occlusion and shows up intersection_occlusion(dyn). if valid, it
93+
//! contains the remaining time to release the static occlusion stuck and shows up
94+
//! intersection_occlusion(x.y)
95+
std::optional<double> static_occlusion_timeout{std::nullopt};
96+
};
97+
98+
/**
99+
* @struct
100+
* @brief both collision and occlusion are detected in the presence of traffic light
101+
*/
102+
struct OccludedCollisionStop
103+
{
104+
bool is_actually_occlusion_cleared{false};
105+
bool temporal_stop_before_attention_required{false};
106+
size_t closest_idx{0};
107+
size_t collision_stopline_idx{0};
108+
size_t first_attention_stopline_idx{0};
109+
size_t occlusion_stopline_idx{0};
110+
//! if null, it is dynamic occlusion and shows up intersection_occlusion(dyn). if valid, it
111+
//! contains the remaining time to release the static occlusion stuck
112+
std::optional<double> static_occlusion_timeout{std::nullopt};
113+
};
114+
115+
/**
116+
* @struct
117+
* @brief at least occlusion is detected in the absence of traffic light
118+
*/
119+
struct OccludedAbsenceTrafficLight
120+
{
121+
bool is_actually_occlusion_cleared{false};
122+
bool collision_detected{false};
123+
bool temporal_stop_before_attention_required{false};
124+
size_t closest_idx{0};
125+
size_t first_attention_area_stopline_idx{0};
126+
size_t peeking_limit_line_idx{0};
127+
};
128+
129+
/**
130+
* @struct
131+
* @brief both collision and occlusion are not detected
132+
*/
133+
struct Safe
134+
{
135+
size_t closest_idx{0};
136+
size_t collision_stopline_idx{0};
137+
size_t occlusion_stopline_idx{0};
138+
};
139+
140+
/**
141+
* @struct
142+
* @brief traffic light is red or arrow signal
143+
*/
144+
struct FullyPrioritized
145+
{
146+
bool collision_detected{false};
147+
size_t closest_idx{0};
148+
size_t collision_stopline_idx{0};
149+
size_t occlusion_stopline_idx{0};
150+
};
151+
152+
using DecisionResult = std::variant<
153+
Indecisive, //! internal process error, or over the pass judge line
154+
StuckStop, //! detected stuck vehicle
155+
YieldStuckStop, //! detected yield stuck vehicle
156+
NonOccludedCollisionStop, //! detected collision while FOV is clear
157+
FirstWaitBeforeOcclusion, //! stop for a while before peeking to occlusion
158+
PeekingTowardOcclusion, //! peeking into occlusion while collision is not detected
159+
OccludedCollisionStop, //! occlusion and collision are both detected
160+
OccludedAbsenceTrafficLight, //! occlusion is detected in the absence of traffic light
161+
Safe, //! judge as safe
162+
FullyPrioritized //! only detect vehicles violating traffic rules
163+
>;
164+
165+
inline std::string formatDecisionResult(const DecisionResult & decision_result)
166+
{
167+
if (std::holds_alternative<Indecisive>(decision_result)) {
168+
const auto indecisive = std::get<Indecisive>(decision_result);
169+
return "Indecisive because " + indecisive.error;
170+
}
171+
if (std::holds_alternative<StuckStop>(decision_result)) {
172+
return "StuckStop";
173+
}
174+
if (std::holds_alternative<YieldStuckStop>(decision_result)) {
175+
return "YieldStuckStop";
176+
}
177+
if (std::holds_alternative<NonOccludedCollisionStop>(decision_result)) {
178+
return "NonOccludedCollisionStop";
179+
}
180+
if (std::holds_alternative<FirstWaitBeforeOcclusion>(decision_result)) {
181+
return "FirstWaitBeforeOcclusion";
182+
}
183+
if (std::holds_alternative<PeekingTowardOcclusion>(decision_result)) {
184+
return "PeekingTowardOcclusion";
185+
}
186+
if (std::holds_alternative<OccludedCollisionStop>(decision_result)) {
187+
return "OccludedCollisionStop";
188+
}
189+
if (std::holds_alternative<OccludedAbsenceTrafficLight>(decision_result)) {
190+
return "OccludedAbsenceTrafficLight";
191+
}
192+
if (std::holds_alternative<Safe>(decision_result)) {
193+
return "Safe";
194+
}
195+
if (std::holds_alternative<FullyPrioritized>(decision_result)) {
196+
return "FullyPrioritized";
197+
}
198+
return "";
199+
}
200+
201+
} // namespace behavior_velocity_planner::intersection
202+
203+
#endif // DECISION_RESULT_HPP_

planning/behavior_velocity_intersection_module/src/util_type.hpp planning/behavior_velocity_intersection_module/src/interpolated_path_info.hpp

+6-14
Original file line numberDiff line numberDiff line change
@@ -12,26 +12,18 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef UTIL_TYPE_HPP_
16-
#define UTIL_TYPE_HPP_
15+
#ifndef INTERPOLATED_PATH_INFO_HPP_
16+
#define INTERPOLATED_PATH_INFO_HPP_
1717

18-
#include <tier4_autoware_utils/geometry/geometry.hpp>
19-
20-
#include <autoware_auto_perception_msgs/msg/predicted_objects.hpp>
2118
#include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
22-
#include <geometry_msgs/msg/point.hpp>
23-
#include <geometry_msgs/msg/polygon.hpp>
24-
#include <geometry_msgs/msg/pose.hpp>
2519

26-
#include <lanelet2_core/primitives/CompoundPolygon.h>
27-
#include <lanelet2_core/primitives/Lanelet.h>
20+
#include <lanelet2_core/Forward.h>
2821

2922
#include <optional>
3023
#include <set>
3124
#include <utility>
32-
#include <vector>
3325

34-
namespace behavior_velocity_planner::util
26+
namespace behavior_velocity_planner::intersection
3527
{
3628

3729
/**
@@ -52,6 +44,6 @@ struct InterpolatedPathInfo
5244
std::optional<std::pair<size_t, size_t>> lane_id_interval{std::nullopt};
5345
};
5446

55-
} // namespace behavior_velocity_planner::util
47+
} // namespace behavior_velocity_planner::intersection
5648

57-
#endif // UTIL_TYPE_HPP_
49+
#endif // INTERPOLATED_PATH_INFO_HPP_
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,82 @@
1+
// Copyright 2024 Tier IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include "intersection_lanelets.hpp"
16+
17+
#include "util.hpp"
18+
19+
#include <lanelet2_core/LaneletMap.h>
20+
#include <lanelet2_routing/RoutingGraph.h>
21+
22+
#include <string>
23+
24+
namespace behavior_velocity_planner::intersection
25+
{
26+
27+
void IntersectionLanelets::update(
28+
const bool is_prioritized, const InterpolatedPathInfo & interpolated_path_info,
29+
const tier4_autoware_utils::LinearRing2d & footprint, const double vehicle_length,
30+
lanelet::routing::RoutingGraphPtr routing_graph_ptr)
31+
{
32+
is_prioritized_ = is_prioritized;
33+
// find the first conflicting/detection area polygon intersecting the path
34+
if (!first_conflicting_area_) {
35+
auto first = util::getFirstPointInsidePolygonsByFootprint(
36+
conflicting_area_, interpolated_path_info, footprint, vehicle_length);
37+
if (first) {
38+
first_conflicting_lane_ = conflicting_.at(first.value().second);
39+
first_conflicting_area_ = conflicting_area_.at(first.value().second);
40+
}
41+
}
42+
if (!first_attention_area_) {
43+
const auto first = util::getFirstPointInsidePolygonsByFootprint(
44+
attention_non_preceding_area_, interpolated_path_info, footprint, vehicle_length);
45+
if (first) {
46+
first_attention_lane_ = attention_non_preceding_.at(first.value().second);
47+
first_attention_area_ = attention_non_preceding_area_.at(first.value().second);
48+
}
49+
}
50+
if (first_attention_lane_ && !second_attention_lane_ && !second_attention_lane_empty_) {
51+
const auto first_attention_lane = first_attention_lane_.value();
52+
// remove first_attention_area_ and non-straight lanelets from attention_non_preceding
53+
lanelet::ConstLanelets attention_non_preceding_ex_first;
54+
lanelet::ConstLanelets sibling_first_attention_lanelets;
55+
for (const auto & previous : routing_graph_ptr->previous(first_attention_lane)) {
56+
for (const auto & following : routing_graph_ptr->following(previous)) {
57+
sibling_first_attention_lanelets.push_back(following);
58+
}
59+
}
60+
for (const auto & ll : attention_non_preceding_) {
61+
// the sibling lanelets of first_attention_lanelet are ruled out
62+
if (lanelet::utils::contains(sibling_first_attention_lanelets, ll)) {
63+
continue;
64+
}
65+
if (std::string(ll.attributeOr("turn_direction", "else")).compare("straight") == 0) {
66+
attention_non_preceding_ex_first.push_back(ll);
67+
}
68+
}
69+
if (attention_non_preceding_ex_first.empty()) {
70+
second_attention_lane_empty_ = true;
71+
}
72+
const auto attention_non_preceding_ex_first_area =
73+
util::getPolygon3dFromLanelets(attention_non_preceding_ex_first);
74+
const auto second = util::getFirstPointInsidePolygonsByFootprint(
75+
attention_non_preceding_ex_first_area, interpolated_path_info, footprint, vehicle_length);
76+
if (second) {
77+
second_attention_lane_ = attention_non_preceding_ex_first.at(second.value().second);
78+
second_attention_area_ = second_attention_lane_.value().polygon3d();
79+
}
80+
}
81+
}
82+
} // namespace behavior_velocity_planner::intersection

0 commit comments

Comments
 (0)