Skip to content

Commit 37dfa79

Browse files
authored
Merge pull request #1198 from tier4/cherry-pick/pr6608+6585
Cherry pick/pr6608+6585
2 parents 26315fd + 77de25e commit 37dfa79

File tree

5 files changed

+91
-24
lines changed

5 files changed

+91
-24
lines changed

planning/behavior_velocity_intersection_module/src/debug.cpp

+16
Original file line numberDiff line numberDiff line change
@@ -389,6 +389,22 @@ visualization_msgs::msg::MarkerArray IntersectionModule::createDebugMarkerArray(
389389
&debug_marker_array, now);
390390
}
391391

392+
if (debug_data_.nearest_occlusion_triangle) {
393+
const auto [p1, p2, p3] = debug_data_.nearest_occlusion_triangle.value();
394+
const auto color = debug_data_.static_occlusion ? green : red;
395+
geometry_msgs::msg::Polygon poly;
396+
poly.points.push_back(
397+
geometry_msgs::build<geometry_msgs::msg::Point32>().x(p1.x).y(p1.y).z(p1.z));
398+
poly.points.push_back(
399+
geometry_msgs::build<geometry_msgs::msg::Point32>().x(p2.x).y(p2.y).z(p2.z));
400+
poly.points.push_back(
401+
geometry_msgs::build<geometry_msgs::msg::Point32>().x(p3.x).y(p3.y).z(p3.z));
402+
appendMarkerArray(
403+
debug::createPolygonMarkerArray(
404+
poly, "nearest_occlusion_triangle", lane_id_, now, 0.3, 0.0, 0.0, std::get<0>(color),
405+
std::get<1>(color), std::get<2>(color)),
406+
&debug_marker_array, now);
407+
}
392408
if (debug_data_.traffic_light_observation) {
393409
const auto GREEN = autoware_perception_msgs::msg::TrafficSignalElement::GREEN;
394410
const auto YELLOW = autoware_perception_msgs::msg::TrafficSignalElement::AMBER;

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

+6-5
Original file line numberDiff line numberDiff line change
@@ -148,17 +148,18 @@ static std::string formatOcclusionType(const IntersectionModule::OcclusionType &
148148
intersection::DecisionResult IntersectionModule::modifyPathVelocityDetail(
149149
PathWithLaneId * path, [[maybe_unused]] StopReason * stop_reason)
150150
{
151-
const auto traffic_prioritized_level = getTrafficPrioritizedLevel();
152-
const bool is_prioritized =
153-
traffic_prioritized_level == TrafficPrioritizedLevel::FULLY_PRIORITIZED;
154-
155-
const auto prepare_data = prepareIntersectionData(is_prioritized, path);
151+
const auto prepare_data = prepareIntersectionData(path);
156152
if (!prepare_data) {
157153
return prepare_data.err();
158154
}
159155
const auto [interpolated_path_info, intersection_stoplines, path_lanelets] = prepare_data.ok();
160156
const auto & intersection_lanelets = intersection_lanelets_.value();
161157

158+
// NOTE: this level is based on the updateTrafficSignalObservation() which is latest
159+
const auto traffic_prioritized_level = getTrafficPrioritizedLevel();
160+
const bool is_prioritized =
161+
traffic_prioritized_level == TrafficPrioritizedLevel::FULLY_PRIORITIZED;
162+
162163
// ==========================================================================================
163164
// stuck detection
164165
//

planning/behavior_velocity_intersection_module/src/scene_intersection.hpp

+8-1
Original file line numberDiff line numberDiff line change
@@ -235,6 +235,10 @@ class IntersectionModule : public SceneModuleInterface
235235
std::vector<geometry_msgs::msg::Polygon> occlusion_polygons;
236236
std::optional<std::pair<geometry_msgs::msg::Point, geometry_msgs::msg::Point>>
237237
nearest_occlusion_projection{std::nullopt};
238+
std::optional<
239+
std::tuple<geometry_msgs::msg::Point, geometry_msgs::msg::Point, geometry_msgs::msg::Point>>
240+
nearest_occlusion_triangle{std::nullopt};
241+
bool static_occlusion{false};
238242
std::optional<double> static_occlusion_with_traffic_light_timeout{std::nullopt};
239243

240244
std::optional<std::tuple<geometry_msgs::msg::Pose, lanelet::ConstPoint3d, lanelet::Id, uint8_t>>
@@ -438,6 +442,9 @@ class IntersectionModule : public SceneModuleInterface
438442
//! unavailable)
439443
std::optional<std::pair<lanelet::Id, lanelet::ConstPoint3d>> tl_id_and_point_;
440444
std::optional<TrafficSignalStamped> last_tl_valid_observation_{std::nullopt};
445+
446+
//! save previous priority level to detect change from NotPrioritized to Prioritized
447+
TrafficPrioritizedLevel previous_prioritized_level_{TrafficPrioritizedLevel::NOT_PRIORITIZED};
441448
/** @} */
442449

443450
private:
@@ -544,7 +551,7 @@ class IntersectionModule : public SceneModuleInterface
544551
* To simplify modifyPathVelocityDetail(), this function is used at first
545552
*/
546553
intersection::Result<BasicData, intersection::InternalError> prepareIntersectionData(
547-
const bool is_prioritized, PathWithLaneId * path);
554+
PathWithLaneId * path);
548555

549556
/**
550557
* @brief find the associated stopline road marking of assigned lanelet

planning/behavior_velocity_intersection_module/src/scene_intersection_occlusion.cpp

+48-11
Original file line numberDiff line numberDiff line change
@@ -47,10 +47,23 @@ IntersectionModule::getOcclusionStatus(
4747
(planner_param_.occlusion.enable && !occlusion_attention_lanelets.empty() && !is_amber_or_red)
4848
? detectOcclusion(interpolated_path_info)
4949
: NotOccluded{};
50-
occlusion_stop_state_machine_.setStateWithMarginTime(
51-
std::holds_alternative<NotOccluded>(occlusion_status) ? StateMachine::State::GO
52-
: StateMachine::STOP,
53-
logger_.get_child("occlusion_stop"), *clock_);
50+
51+
// ==========================================================================================
52+
// if the traffic light changed from green to yellow/red, hysteresis time for occlusion is
53+
// unnecessary
54+
// ==========================================================================================
55+
const auto transition_to_prioritized =
56+
(previous_prioritized_level_ == TrafficPrioritizedLevel::NOT_PRIORITIZED &&
57+
traffic_prioritized_level != TrafficPrioritizedLevel::NOT_PRIORITIZED);
58+
if (transition_to_prioritized) {
59+
occlusion_stop_state_machine_.setState(StateMachine::State::GO);
60+
} else {
61+
occlusion_stop_state_machine_.setStateWithMarginTime(
62+
std::holds_alternative<NotOccluded>(occlusion_status) ? StateMachine::State::GO
63+
: StateMachine::STOP,
64+
logger_.get_child("occlusion_stop"), *clock_);
65+
}
66+
5467
const bool is_occlusion_cleared_with_margin =
5568
(occlusion_stop_state_machine_.getState() == StateMachine::State::GO); // module's detection
5669
// distinguish if ego detected occlusion or RTC detects occlusion
@@ -318,13 +331,14 @@ IntersectionModule::OcclusionType IntersectionModule::detectOcclusion(
318331
}
319332
return nearest;
320333
};
321-
struct NearestOcclusionPoint
334+
struct NearestOcclusionInterval
322335
{
323336
int64 division_index{0};
324337
int64 point_index{0};
325338
double dist{0.0};
326339
geometry_msgs::msg::Point point;
327340
geometry_msgs::msg::Point projection;
341+
geometry_msgs::msg::Point visible_end;
328342
} nearest_occlusion_point;
329343
double min_dist = std::numeric_limits<double>::infinity();
330344
for (unsigned division_index = 0; division_index < lane_divisions.size(); ++division_index) {
@@ -354,6 +368,8 @@ IntersectionModule::OcclusionType IntersectionModule::detectOcclusion(
354368
continue;
355369
}
356370
double acc_dist = 0.0;
371+
bool found_min_dist_for_this_division = false;
372+
bool is_prev_occluded = false;
357373
auto acc_dist_it = projection_it;
358374
for (auto point_it = projection_it; point_it != division.end(); point_it++) {
359375
const double dist =
@@ -370,11 +386,24 @@ IntersectionModule::OcclusionType IntersectionModule::detectOcclusion(
370386
if (acc_dist < min_dist) {
371387
min_dist = acc_dist;
372388
nearest_occlusion_point = {
373-
division_index, std::distance(division.begin(), point_it), acc_dist,
389+
division_index,
390+
std::distance(division.begin(), point_it),
391+
acc_dist,
374392
tier4_autoware_utils::createPoint(point_it->x(), point_it->y(), origin.z),
375-
tier4_autoware_utils::createPoint(projection_it->x(), projection_it->y(), origin.z)};
393+
tier4_autoware_utils::createPoint(projection_it->x(), projection_it->y(), origin.z),
394+
tier4_autoware_utils::createPoint(
395+
projection_it->x(), projection_it->y(),
396+
origin.z) /* initialize with projection point at first*/};
397+
found_min_dist_for_this_division = true;
398+
} else if (found_min_dist_for_this_division && is_prev_occluded) {
399+
// although this cell is not "nearest" cell, we have found the "nearest" cell on this
400+
// division previously in this iteration, and the iterated cells are still OCCLUDED since
401+
// then
402+
nearest_occlusion_point.visible_end =
403+
tier4_autoware_utils::createPoint(point_it->x(), point_it->y(), origin.z);
376404
}
377405
}
406+
is_prev_occluded = (pixel == OCCLUDED);
378407
}
379408
}
380409

@@ -384,16 +413,24 @@ IntersectionModule::OcclusionType IntersectionModule::detectOcclusion(
384413

385414
debug_data_.nearest_occlusion_projection =
386415
std::make_pair(nearest_occlusion_point.point, nearest_occlusion_point.projection);
387-
LineString2d ego_occlusion_line;
388-
ego_occlusion_line.emplace_back(current_pose.position.x, current_pose.position.y);
389-
ego_occlusion_line.emplace_back(nearest_occlusion_point.point.x, nearest_occlusion_point.point.y);
416+
debug_data_.nearest_occlusion_triangle = std::make_tuple(
417+
current_pose.position, nearest_occlusion_point.point, nearest_occlusion_point.visible_end);
418+
Polygon2d ego_occlusion_triangle;
419+
ego_occlusion_triangle.outer().emplace_back(current_pose.position.x, current_pose.position.y);
420+
ego_occlusion_triangle.outer().emplace_back(
421+
nearest_occlusion_point.point.x, nearest_occlusion_point.point.y);
422+
ego_occlusion_triangle.outer().emplace_back(
423+
nearest_occlusion_point.visible_end.x, nearest_occlusion_point.visible_end.y);
424+
bg::correct(ego_occlusion_triangle);
390425
for (const auto & attention_object_info : object_info_manager_.allObjects()) {
391426
const auto obj_poly =
392427
tier4_autoware_utils::toPolygon2d(attention_object_info->predicted_object());
393-
if (bg::intersects(obj_poly, ego_occlusion_line)) {
428+
if (bg::intersects(obj_poly, ego_occlusion_triangle)) {
429+
debug_data_.static_occlusion = false;
394430
return DynamicallyOccluded{min_dist};
395431
}
396432
}
433+
debug_data_.static_occlusion = true;
397434
return StaticallyOccluded{min_dist};
398435
}
399436
} // namespace behavior_velocity_planner

planning/behavior_velocity_intersection_module/src/scene_intersection_prepare_data.cpp

+13-7
Original file line numberDiff line numberDiff line change
@@ -166,7 +166,7 @@ using intersection::make_ok;
166166
using intersection::Result;
167167

168168
Result<IntersectionModule::BasicData, intersection::InternalError>
169-
IntersectionModule::prepareIntersectionData(const bool is_prioritized, PathWithLaneId * path)
169+
IntersectionModule::prepareIntersectionData(PathWithLaneId * path)
170170
{
171171
const auto lanelet_map_ptr = planner_data_->route_handler_->getLaneletMapPtr();
172172
const auto routing_graph_ptr = planner_data_->route_handler_->getRoutingGraphPtr();
@@ -175,6 +175,18 @@ IntersectionModule::prepareIntersectionData(const bool is_prioritized, PathWithL
175175
const auto footprint = planner_data_->vehicle_info_.createFootprint(0.0, 0.0);
176176
const auto & current_pose = planner_data_->current_odometry->pose;
177177

178+
// ==========================================================================================
179+
// update traffic light information
180+
// updateTrafficSignalObservation() must be called at first because other traffic signal
181+
// fuctions use last_valid_observation_
182+
// ==========================================================================================
183+
// save previous information before calling updateTrafficSignalObservation()
184+
previous_prioritized_level_ = getTrafficPrioritizedLevel();
185+
updateTrafficSignalObservation();
186+
const auto traffic_prioritized_level = getTrafficPrioritizedLevel();
187+
const bool is_prioritized =
188+
traffic_prioritized_level == TrafficPrioritizedLevel::FULLY_PRIORITIZED;
189+
178190
// spline interpolation
179191
const auto interpolated_path_info_opt = util::generateInterpolatedPath(
180192
lane_id_, associative_ids_, *path, planner_param_.common.path_interpolation_ds, logger_);
@@ -264,13 +276,7 @@ IntersectionModule::prepareIntersectionData(const bool is_prioritized, PathWithL
264276
planner_data_->occupancy_grid->info.resolution);
265277
}
266278

267-
// ==========================================================================================
268-
// update traffic light information
269-
// updateTrafficSignalObservation() must be called at first to because other traffic signal
270-
// fuctions use last_valid_observation_
271-
// ==========================================================================================
272279
if (has_traffic_light_) {
273-
updateTrafficSignalObservation();
274280
const bool is_green_solid_on = isGreenSolidOn();
275281
if (is_green_solid_on && !initial_green_light_observed_time_) {
276282
const auto assigned_lane_begin_point = assigned_lanelet.centerline().front();

0 commit comments

Comments
 (0)