diff --git a/planning/behavior_velocity_intersection_module/README.md b/planning/behavior_velocity_intersection_module/README.md index 3ed4ee8fd334a..12455a26d2f4a 100644 --- a/planning/behavior_velocity_intersection_module/README.md +++ b/planning/behavior_velocity_intersection_module/README.md @@ -1,46 +1,67 @@ -## Intersection +# Intersection -### Role +## Role -The _intersection_ module is responsible for safely going through urban intersections by: +The intersection module is responsible for safely passing urban intersections by: 1. checking collisions with upcoming vehicles 2. recognizing the occluded area in the intersection -3. reacting to arrow signals of associated traffic lights +3. reacting to each color/shape of associated traffic lights -The module is designed to be agnostic to left-hand/right-hand traffic rules and works on crossroads, T-shape junctions, etc. +This module is designed to be agnostic to left-hand/right-hand traffic rules and work for crossroads, T-shape junctions, etc. Roundabout is not formally supported in this module. ![topology](./docs/intersection-topology.drawio.svg) -### Activation condition +## Activation condition -This module is activated when the path contains the lanes with `turn_direction` tag. More precisely, if the `lane_ids` of the path contains the ids of those lanes, corresponding instances of intersection module are activated on each lanes respectively. +This module is activated when the path contains the lanes with turn_direction tag. More precisely, if the lane_ids of the path contain the ids of those lanes, corresponding instances of intersection module are activated on each lane respectively. -### Requirements/Limitations +## Requirements/Limitations -- The HDMap needs to have the information of `turn_direction` tag (which should be one of `straight`, `left`, `right`) for all the lanes in intersections and `right_of_way` tag for specific lanes (refer to [RightOfWay](#right-of-way) section for more details). See [lanelet2_extension document](https://github.com/autowarefoundation/autoware_common/blob/main/tmp/lanelet2_extension/docs/lanelet2_format_extension.md) for more detail. +- The HDMap needs to have the information of turn_direction tag (which should be one of straight, left, right) for all the lanes in intersections and right_of_way tag for specific lanes (refer to [RightOfWay](#how-towhy-set-rightofway-tag) section for more details). See [lanelet2_extension document](https://github.com/autowarefoundation/autoware_common/blob/main/tmp/lanelet2_extension/docs/lanelet2_format_extension.md) for more detail. - WIP(perception requirements/limitations) - WIP(sensor visibility requirements/limitations) -### Attention area - -The `attention area` in the intersection are defined as the set of lanes that are conflicting with ego vehicle's path and their preceding lanes up to `common.attention_area_length` meters. `RightOfWay` tag is used to rule out the lanes that each lane has priority given the traffic light relation and `turn_direction` priority(`yield lane`). +## Attention area -`Intersection Area`, which is supposed to be defined on the HDMap, is an area converting the entire intersection. +The attention area in the intersection is defined as the set of lanes that are conflicting with ego path and their preceding lanes up to `common.attention_area_length` meters. By default RightOfWay tag is not set, so the attention area covers all the conflicting lanes and its preceding lanes as shown in the first row. RightOfWay tag is used to rule out the lanes that each lane has priority given the traffic light relation and turn_direction priority. In the second row, purple lanes are set as the yield_lane of the ego_lane in the RightOfWay tag. ![attention_area](./docs/intersection-attention.drawio.svg) -#### Right Of Way +intersection_area, which is supposed to be defined on the HDMap, is an area converting the entire intersection. + +### In-phase/Anti-phase signal group + +The terms "in-phase signal group" and "anti-phase signal group" are introduced to distinguish the lanes by the timing of traffic light regulation as shown in below figure. + +![phase signal group](./docs/signal-phase-group.drawio.svg) + +The set of intersection lanes whose color is in sync with lane L1 is called the in-phase signal group of L1, and the set of remaining lanes is called the anti-phase signal group. + +### How-to/Why set RightOfWay tag + +Ideally RightOfWay tag is unnecessary if ego has perfect knowledge of all traffic signal information because: -Following table shows an example of how to assign `right_of_way` tag and set `yield_lanes` to each lane in intersections. +- it can distinguish which conflicting lanes should be checked because they are GREEN currently and possible collision occur with the vehicles on those lanes +- it can distinguish which conflicting lanes can be ignored because they are RED currently and there is no chance of collision with the vehicles on those lanes unless they violate the traffic rule -| turn direction / traffic light | w/ traffic light | w/o traffic light | -| ------------------------------ | --------------------------------------------------------------- | ------------------------------------------------ | -| straight | Highest priority of all | Priority over left/right lanes of the same group | -| left(Left hand traffic) | Priority over the other group and right lanes of the same group | Priority over right lanes of the same group | -| right(Left hand traffic) | Priority only over the other group | priority only over the other group | -| left(Right hand traffic) | Priority only over the other group | Priority only over the other group | -| right(Right hand traffic) | Priority over the other group and left lanes of the same group | priority over left lanes of the same group | +That allows ego to generate the attention area dynamically using the real time traffic signal information. However this ideal condition rarely holds unless the traffic signal information is provided through the infrastructure. Also there maybe be very complicated/bad intersection maps where multiple lanes overlap in a complex manner. + +- If there is an perfect access to entire traffic light signal, then you can set `common.use_map_right_of_way` to false and there is no need to set RightOfWay tag on the map. The intersection module will generate the attention area by checking traffic signal and corresponding conflicting lanes. This feature is not implemented yet. +- If traffic signal information is not perfect, then set `common.use_map_right_of_way` to true. If you do not want to detect vehicles on the anti-phase signal group lanes, set them as yield_lane for ego lane. +- Even if there are no traffic lights if the intersection lanes are overlapped in a ugly manner, you may need to set RightOfWay tag. For example if adjacent intersection lanes of the same in-phase group are not sharing the boundary line and overlapped a little bit, you may need to set RightOfWay to each other for them in order to avoid unnecessary stop for vehicle on such unrelated lane. + +To help the intersection module care only a set of limited lanes, RightOfWay tag needs to be properly set. + +Following table shows an **example** of how to set yield_lanes to each lane in a intersection w/o traffic lights. Since it is not apparent how to uniquely determine signal phase group for a set of intersection lanes in geometric/topological manner, yield_lane needs to be set manually. Straight lanes with traffic lights are exceptionally handled to detect no lanes because commonly it has priority over all the other lanes, so no RightOfWay setting is required. + +| turn direction of right_of_way | yield_lane(with traffic light) | yield_lane(without traffic light) | +| ------------------------------ | ------------------------------------------------------------------------------------------- | ---------------------------------------------- | +| straight | not need to set yield_lane(this case is special) | left/right conflicting lanes of in-phase group | +| left(Left hand traffic) | all conflicting lanes of the anti-phase group and right conflicting lanes of in-phase group | right conflicting lanes of in-phase group | +| right(Left hand traffic) | all conflicting lanes of the anti-phase group | no yield_lane | +| left(Right hand traffic) | all conflicting lanes of the anti-phase group | no yield_lane | +| right(Right hand traffic) | all conflicting lanes of the anti-phase group and right conflicting lanes of in-phase group | left conflicting lanes of in-phase group | This setting gives the following `attention_area` configurations. @@ -48,45 +69,141 @@ This setting gives the following `attention_area` configurations. ![attention_area_ll_rr](./docs/intersection-attention-ll-rr.drawio.svg) ![attention_area_lr_rl](./docs/intersection-attention-lr-rl.drawio.svg) -### Target objects +For complex/bad intersection map like the one illustrated below, additional RightOfWay setting maybe necessary. + +![bad-map](./docs/ugly-intersection.drawio.svg) + +The bad points are: + +1. ego lane is overlapped with adjacent lane of the in-phase group. In this case you need to set this lane as yield_lane additionally because otherwise attention area is generated for its preceding lanes as well, which may cause unwanted stop. +2. ego lane is overlapped with unrelated lane. In this case the lane is right-turn only and there is no chance of collision in theory. But you need to set this lane as yield_lane additionally for the same reason as (1). + +## Possible stop lines + +Following figure illustrates important positions used in the intersection module. Note that each solid line represents ego front line position and the corresponding dot represents the actual inserted stop point position for the vehicle frame, namely the center of the rear wheel. + +![data structure](./docs/intersection-stoplines.drawio.svg) + +To precisely calculate stop positions, the path is interpolated at the certain interval of `common.path_interpolation_ds`. + +- closest_idx denotes the path point index which is closest to ego position. +- first_attention_stopline denotes the first path point where ego footprint intersects with the attention_area. +- If a stopline is associated with the intersection lane on the map, that line is used as the default_stopline for collision detection. Otherwise the point which is `common.default_stopline_margin` meters behind first_attention_stopline is defined as the default_stopline instead. +- occlusion_peeking_stopline is a bit ahead of first_attention_stopline as described later. +- occlusion_wo_tl_pass_judge_line is the first position where ego footprint intersects with the centerline of the first attention_area lane. + +## Target objects For [stuck vehicle detection](#stuck-vehicle-detection) and [collision detection](#collision-detection), this module checks **car**, **bus**, **truck**, **trailer**, **motor cycle**, and **bicycle** type objects. Objects that satisfy all of the following conditions are considered as target objects (possible collision objects): -- The center of mass of the object is **within a certain distance** from the attention lane (threshold = `common.attention_area_margin`) . - - (Optional condition) The center of gravity is in the **intersection area**. +- The center of the object is **within a certain distance** from the attention lane (threshold = `common.attention_area_margin`) . + - (Optional condition) The center of the object is in the **intersection area**. - To deal with objects that is in the area not covered by the lanelets in the intersection. - The posture of object is **the same direction as the attention lane** (threshold = `common.attention_area_angle_threshold`). -- Not being **in the adjacent lanes of the ego vehicle**. +- Not being **in the adjacent lanes of ego**. + +## Overview of decision process + +There are several behaviors depending on the scene. + +| behavior | scene | action | +| ------------------------ | ------------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------- | +| Safe | Ego detected no occlusion and collision | Ego passes the intersection | +| StuckStop | The exit of the intersection is blocked by traffic jam | Ego stops before the intersection or the boundary of attention area | +| YieldStuck | Another vehicle stops to yield ego | Ego stops before the intersection or the boundary of attention area | +| NonOccludedCollisionStop | Ego detects no occlusion but detects collision | Ego stops at the default_stop_line | +| FirstWaitBeforeOcclusion | Ego detected occlusion when entering the intersection | Ego stops at the default_stop_line at first | +| PeekingTowardOcclusion | Ego detected occlusion and but no collision within the FOV (after FirstWaitBeforeOcclusion) | Ego approaches the boundary of the attention area slowly | +| OccludedCollisionStop | Ego detected both occlusion and collision (after FirstWaitBeforeOcclusion) | Ego stops immediately | +| FullyPrioritized | Ego is fully prioritized by the RED/Arrow signal | Ego only cares vehicles still running inside the intersection. Occlusion is ignored | +| OverPassJudgeLine | Ego is already inside the attention area and/or cannot stop before the boundary of attention area | Ego does not detect collision/occlusion anymore and passes the intersection | + +```plantuml +@startuml + +state begin <> +[*] --> begin +begin --> OverPassJudgeLine: IF over_pass_judge + +state "Before pass judge line" as NotOverPassJudgeLine { +state check_stuck <> +begin --> check_stuck: ELSE + +check_stuck --> StuckStop: IF stuck vehicle detected + +state check_yield_stuck <> +check_stuck --> check_yield_stuck: ELSE +check_yield_stuck --> YieldStuck: IF yield stuck vehicle detected + +state check_tl_priority <> +check_yield_stuck --> check_tl_priority: ELSE -#### Stuck Vehicle Detection +state check_occlusion <> +check_tl_priority --> check_occlusion: IF not prioritized -If there is any object on the path in inside the intersection and at the exit of the intersection (up to `stuck_vehicle_detect_dist`) lane and its velocity is less than a threshold (`stuck_vehicle.stuck_vehicle_vel_thr`), the object is regarded as a stuck vehicle. If stuck vehicles exist, this module inserts a stopline a certain distance (=`stop_line_margin`) before the overlapped region with other lanes. The stuck vehicle detection area is generated based on the vehicle path, so the stuck vehicle stopline is not inserted if the upstream module generated avoidance path +state Safe +State "Prioritized by traffic light" as Prioritized { +state check_collision_prioritized <> +check_tl_priority --> check_collision_prioritized: IF prioritized +State FullyPrioritized +check_collision_prioritized --> FullyPrioritized: IF collision detected +check_collision_prioritized --> Safe: ELSE +} + +check_occlusion --> Occlusion: IF occlusion is detected + +State "Occlusion is not detected" as NoOcclusion { +state check_collision <> +check_occlusion --> check_collision: ELSE +State NonOccludedCollisionStop +check_collision --> Safe: ELSE +check_collision --> NonOccludedCollisionStop: IF collision detected +} + +State "Occlusion is detected" as Occlusion { +state FirstWaitBeforeOcclusion +FirstWaitBeforeOcclusion --> Peeking: after termporal stop +state Peeking { +State PeekingTowardOcclusion +State OccludedCollisionStop +PeekingTowardOcclusion --> OccludedCollisionStop : IF collision detected +OccludedCollisionStop --> PeekingTowardOcclusion: IF not collision detected +} +} + +} + +@enduml +``` + +## Stuck Vehicle Detection + +If there is any object on the path inside the intersection and at the exit of the intersection (up to `stuck_vehicle.stuck_vehicle_detect_dist`) lane and its velocity is less than the threshold (`stuck_vehicle.stuck_vehicle_velocity_threshold`), the object is regarded as a stuck vehicle. If stuck vehicles exist, this module inserts a stopline a certain distance (=`default_stopline_margin`) before the overlapped region with other lanes. The stuck vehicle detection area is generated based on the planned path, so the stuck vehicle stopline is not inserted if the upstream module generated an avoidance path. ![stuck_vehicle_detection](./docs/stuck-vehicle.drawio.svg) -#### Collision detection +## Collision detection -The following process is performed for the targets objects to determine whether the ego vehicle can pass the intersection safely. If it is judged that the ego vehicle cannot pass through the intersection with enough margin, this module inserts a stopline on the path. +The following process is performed for the targets objects to determine whether ego can pass the intersection safely. If it is judged that ego cannot pass the intersection with enough margin, this module inserts a stopline on the path. -1. calculate the time interval that the ego vehicle is in the intersection. This time is set as $t_s$ ~ $t_e$ -2. extract the predicted path of the target object whose confidence is greater than `collision_detection.min_predicted_path_confidence`. -3. detect collision between the extracted predicted path and ego's predicted path in the following process. - 1. obtain the passing area of the ego vehicle $A_{ego}$ in $t_s$ ~ $t_e$. - 2. calculate the passing area of the target object $A_{target}$ at $t_s$ - `collision_detection.collision_start_margin_time` ~ $t_e$ + `collision_detection.collision_end_margin_time` for each predicted path (\*1). - 3. check if $A_{ego}$ and $A_{target}$ polygons are overlapped (has collision). -4. when a collision is detected, the module inserts a stopline. -5. If ego is over the `pass_judge_line`, collision checking is not processed to avoid sudden braking and/or unnecessary stop in the middle of the intersection. +1. predict the time $t$ when the object intersects with ego path for the first time from the predicted path time step. Only the predicted whose confidence is greater than `collision_detection.min_predicted_path_confidence` is used. +2. detect collision between the predicted path and ego's predicted path in the following process + 1. calculate the collision interval of [$t$ - `collision_detection.collision_start_margin_time`, $t$ + `collision_detection.collision_end_margin_time`] + 2. calculate the passing area of ego during the collision interval from the array of (time, distance) obtained by smoothed velocity profile + 3. check if ego passing area and object predicted path interval collides +3. if collision is detected, the module inserts a stopline +4. if ego is over the [pass_judge_line](#pass-judge-line), collision checking is skipped to avoid sudden braking and/or unnecessary stop in the middle of the intersection The parameters `collision_detection.collision_start_margin_time` and `collision_detection.collision_end_margin_time` can be interpreted as follows: -- If the ego vehicle was to pass through the intersection earlier than the target object, collision would be detected if the time difference between the two was less than `collision_detection.collision_start_margin_time`. -- If the ego vehicle was to pass through the intersection later than the target object, collision would be detected if the time difference between the two was less than `collision_detection.collision_end_margin_time`. +- If ego was to pass the intersection earlier than the target object, collision would be detected if the time difference between the two was less than `collision_detection.collision_start_margin_time`. +- If ego was to pass the intersection later than the target object, collision would be detected if the time difference between the two was less than `collision_detection.collision_end_margin_time`. -If collision is detected, the state transits to "STOP" immediately. On the other hand, the state does not transit to "GO" unless safe judgement continues for a certain period `collision_detection.state_transit_margin` to prevent the chattering of decisions. +If collision is detected, the state transits to "STOP" immediately. On the other hand, the state does not transit to "GO" unless safe judgement continues for a certain period `collision_detection.collision_detection_hold_time` to prevent the chattering of decisions. -Currently, the intersection module uses `motion_velocity_smoother` feature to precisely calculate ego vehicle velocity profile along the intersection lane under longitudinal/lateral constraints. If the flag `collision_detection.use_upstream_velocity` is true, the target velocity profile of the original path is used. Otherwise the target velocity is set to `common.intersection_velocity`. In the trajectory smoothing process the target velocity at/before ego trajectory points are set to ego current velocity. The smoothed trajectory is then converted to an array of (time, distance) which indicates the arrival time to each trajectory point on the path from current ego position. You can visualize this array by adding the lane id to `debug.ttc` and running +Currently, the intersection module uses `motion_velocity_smoother` feature to precisely calculate ego velocity profile along the intersection lane under longitudinal/lateral constraints. If the flag `collision_detection.velocity_profile.use_upstream` is true, the target velocity profile of the original path is used. Otherwise the target velocity is set to `collision.velocity_profile.default_velocity`. In the trajectory smoothing process the target velocity at/before ego trajectory points are set to ego current velocity. The smoothed trajectory is then converted to an array of (time, distance) which indicates the arrival time to each trajectory point on the path from current ego position. You can visualize this array by adding the lane id to `debug.ttc` and running ```bash ros2 run behavior_velocity_intersection_module ttc.py --lane_id @@ -94,42 +211,88 @@ ros2 run behavior_velocity_intersection_module ttc.py --lane_id ![ego ttc profile](./docs/ttc.gif) -#### Stop Line Automatic Generation +## Occlusion detection -If a stopline is associated with the intersection lane on the map, that line is used as the stopline for collision detection. Otherwise the path is interpolated at a certain intervals (=`common.path_interpolation_ds`), and the point which is `stop_line_margin` meters behind the attention area is defined as the position of the stop line for the vehicle front. +If the flag `occlusion.enable` is true this module checks if there is sufficient field of view (FOV) on the attention area up to `occlusion.occlusion_attention_area_length`. If FOV is not clear enough ego first makes a brief stop at the default stop line for `occlusion.temporal_stop_time_before_peeking`, and then slowly creeps toward occlusion_peeking_stop_line. If `occlusion.creep_during_peeking.enable` is true `occlusion.creep_during_peeking.creep_velocity` is inserted up to occlusion_peeking_stop_line. Otherwise only stop line is inserted. -#### Pass Judge Line +During the creeping if collision is detected this module inserts a stop line in front of ego immediately, and if the FOV gets sufficiently clear the intersection_occlusion wall will disappear. If occlusion is cleared and no collision is detected ego will pass the intersection. -To avoid sudden braking, if deceleration and jerk more than a threshold (`behavior_velocity_planner.max_accel` and `behavior_velocity_planner.max_jerk`) is required to stop just in front of the attention area, namely the `first_attention_stop_line`, this module does not insert stopline after it passed the `default stop_line` position. +The occlusion is detected as the common area of occlusion attention area(which is partially the same as the normal attention area) and the unknown cells of the occupancy grid map. The occupancy grid map is denoised using morphology with the window size of `occlusion.denoise_kernel`. The occlusion attention area lanes are discretized to line strings and they are used to generate a grid whose each cell represents the distance from ego path along the lane as shown below. -The position of the pass judge line depends on the occlusion detection configuration and the existence of the associated traffic light of the intersection lane. +![occlusion_detection](./docs/occlusion_grid.drawio.svg) -- If `occlusion.enable` is false, the pass judge line before the `first_attention_stop_line` by the braking distance $v_{ego}^{2} / 2a_{max}$. -- If `occlusion.enable` is true and: - - if there are associated traffic lights, the pass judge line is at the `occlusion_peeking_stop_line` in order to continue peeking/collision detection while occlusion is detected. - - if there are no associated traffic lights and: - - if occlusion is detected, pass judge line is at the `occlusion_wo_tl_pass_judge_line` to continue peeking. - - if occlusion is not detected, pass judge line is at the same place at the case where `occlusion.enable` is false. +If the nearest occlusion cell value is below the threshold `occlusion.occlusion_required_clearance_distance`, it means that the FOV of ego is not clear. It is expected that the occlusion gets cleared as the vehicle approaches the occlusion peeking stop line. -![data structure](./docs/data-structure.drawio.svg) +### Occlusion source estimation at intersection with traffic light -### Occlusion detection +At intersection with traffic light, the whereabout of occlusion is estimated by checking if there are any objects between ego and the nearest occlusion cell. While the occlusion is estimated to be caused by some object (DYNAMICALLY occluded), intersection_wall appears at all times. If no objects are found between ego and the nearest occlusion cell (STATICALLY occluded), after ego stopped for the duration of `occlusion.static_occlusion_with_traffic_light_timeout` plus `occlusion.occlusion_detection_hold_time`, occlusion is intentionally ignored to avoid stuck. -If the flag `occlusion.enable` is true this module checks if there is sufficient field of view (FOV) on the attention area up to `occlusion.occlusion_attention_area_length`. If FOV is not clear enough the ego vehicle will once stop at the _default stop line_ for `occlusion.before_creep_stop_time`, and then slowly creep toward _occlusion peeking stop line_ at the speed of `occlusion.occlusion_creep_velocity` if `occlusion.enable_creeping` is true. During the creeping if collision is detected this module inserts a stop line instantly, and if the FOV gets sufficiently clear the _intersection occlusion_ wall will disappear. If occlusion is cleared and no collision is detected the ego vehicle will pass the intersection. +![occlusion_detection](./docs/occlusion-with-tl.drawio.svg) -The occlusion is detected as the common area of occlusion attention area(which is partially the same as the normal attention area) and the unknown cells of the occupancy grid map. The occupancy grid map is denoised using morphology with the window size of `occlusion.denoise_kernel`. The occlusion attention area lanes are discretized to line strings and they are used to generate a grid whose each cell represents the distance from the ego path along the lane as shown below. +The remaining time is visualized on the intersection_occlusion virtual wall. -![occlusion_detection](./docs/occlusion_grid.drawio.svg) +![static-occlusion-timeout](./docs/static-occlusion-timeout.png) -If the nearest occlusion cell value is below the threshold, occlusion is detected. It is expected that the occlusion gets cleared as the vehicle approaches the occlusion peeking stop line. +### Occlusion handling at intersection without traffic light -In there are no traffic lights associated with the lane, the ego vehicle will make a brief stop at the _default stop line_ and the position where the vehicle heading touches the attention area for the first time(which is denoted as _first attention stop line_). After stopping at the _first attention area stop line_ this module inserts `occlusion.absence_traffic_light.creep_velocity` velocity between ego and the position which is `occlusion.absence_traffic_light.maximum_peeking_distance` ahead of _first attention area stop line_ while occlusion is not cleared. If collision is detected, ego will instantly stop. Once the occlusion is cleared or ego passed `occlusion.absence_traffic_light.maximum_peeking_distance` this module does not detect collision and occlusion because ego vehicle is already inside the intersection. +At intersection without traffic light, if occlusion is detected, ego makes a brief stop at the default_stopline and first_attention_stopline respectively. After stopping at the first_attention_area_stopline this module inserts `occlusion.absence_traffic_light.creep_velocity` velocity between ego and occlusion_wo_tl_pass_judge_line while occlusion is not cleared. If collision is detected, ego immediately stops. Once the occlusion is cleared or ego has passed occlusion_wo_tl_pass_judge_line this module does not detect collision and occlusion because ego footprint is already inside the intersection. ![occlusion_detection](./docs/occlusion-without-tl.drawio.svg) -### Data Structure +While ego is creeping, yellow intersection_wall appears in front ego. + +![occlusion-wo-tl-creeping](./docs/occlusion-wo-tl-creeping.png) + +## Traffic signal specific behavior + +### Collision detection + +TTC parameter varies depending on the traffic light color/shape as follows. + +| traffic light color | ttc(start) | ttc(end) | +| ------------------- | ---------------------------------------------------------------------- | ---------------------------------------------------------------------- | +| GREEN | `collision_detection.not_prioritized.collision_start_margin` | `collision_detection.not_prioritized.collision_end_margin` | +| AMBER | `collision_detection.partially_prioritized.collision_start_end_margin` | `collision_detection.partially_prioritized.collision_start_end_margin` | +| RED / Arrow | `collision_detection.fully_prioritized.collision_start_end_margin` | `collision_detection.fully_prioritized.collision_start_end_margin` | + +### yield on GREEN + +If the traffic light color changed to GREEN and ego approached the entry of the intersection lane within the distance `collision_detection.yield_on_green_traffic_light.distance_to_assigned_lanelet_start` and there is any object whose distance to its stopline is less than `collision_detection.yield_on_green_traffic_light.object_dist_to_stopline`, this module commands to stop for the duration of `collision_detection.yield_on_green_traffic_light.duration` at the default_stopline. + +### skip on AMBER + +If the traffic light color is AMBER but the object is expected to stop before its stopline under the deceleration of `collision_detection.ignore_on_amber_traffic_light.object_expected_deceleration`, collision checking is skipped. + +### skip on RED -#### `IntersectionLanelets` +If the traffic light color is RED or Arrow signal is turned on, the attention lanes which are not conflicting with ego lane are not used for detection. And even if the object stops with a certain overshoot from its stopline, but its expected stop position under the deceleration of `collision_detection.ignore_on_amber_traffic_light.object_expected_deceleration` is more than the distance `collision_detection.ignore_on_red_traffic_light.object_margin_to_path` from collision point, the object is ignored. + +### Occlusion detection + +When the traffic light color/shape is RED/Arrow, occlusion detection is skipped. + +## Pass Judge Line + +To avoid sudden braking, if deceleration and jerk more than the threshold (`common.max_accel` and `common.max_jerk`) is required to stop at first_attention_stopline, this module does not command to stop once it passed the default_stopline position. + +If ego passed pass_judge_line, then ego does not stop anymore. If ego passed pass_judge_line while ego is stopping for dangerous decision, then ego stops while the situation is judged as dangerous. Once the judgement turned safe, ego restarts and does not stop anymore. + +The position of the pass judge line depends on the occlusion detection configuration and the existence of the associated traffic light of the intersection lane. + +- If `occlusion.enable` is false, the pass judge line before the `first_attention_stopline` by the braking distance $v_{ego}^{2} / 2a_{max}$. +- If `occlusion.enable` is true and: + - if there are associated traffic lights, the pass judge line is at the `occlusion_peeking_stopline` in order to continue peeking/collision detection while occlusion is detected. + - if there are no associated traffic lights and: + - if occlusion is detected, pass judge line is at the `occlusion_wo_tl_pass_judge_line` to continue peeking. + - if occlusion is not detected, pass judge line is at the same place at the case where `occlusion.enable` is false. + +## Data Structure + +Each data structure is defined in `util_type.hpp`. + +![data-structure](./docs/data-structure.drawio.svg) + +### `IntersectionLanelets` ```plantuml @startuml @@ -148,12 +311,12 @@ entity IntersectionLanelets { Part of attention lanes/area for occlusion detection -- * is_priortized: bool - If ego vehicle has priority in current traffic light context + If ego has priority in current traffic light context } @enduml ``` -#### `IntersectionStopLines` +### `IntersectionStopLines` Each stop lines are generated from interpolated path points to obtain precise positions. @@ -161,62 +324,172 @@ Each stop lines are generated from interpolated path points to obtain precise po @startuml entity IntersectionStopLines { * closest_idx: size_t - closest path point index for ego vehicle + closest path point index for ego -- - * stuck_stop_line: size_t + * stuck_stopline: size_t stop line index on stuck vehicle detection -- - * default_stop_line: size_t - If defined on the map, its index on the path. Otherwise generated before first_attention_stop_line + * default_stopline: size_t + If defined on the map, its index on the path. Otherwise generated before first_attention_stopline -- - * first_attention_stop_line + * first_attention_stopline The index of the first path point which is inside the attention area -- - * occlusion_peeking_stop_line + * occlusion_peeking_stopline The index of the path point for the peeking limit position -- * pass_judge_line - The index of the path point which is before first_attention_stop_line/occlusion_peeking_stop_line by braking distance + The index of the path point which is before first_attention_stopline/occlusion_peeking_stopline by braking distance } @enduml ``` -### Module Parameters +### `TargetObject` -| Parameter | Type | Description | -| --------------------------------------------------- | ------ | ---------------------------------------------------------------------------------------------- | -| `common.attention_area_margin` | double | [m] margin for expanding attention area width | -| `common.attention_area_length` | double | [m] range for object detection | -| `common.attention_area_angle_threshold` | double | [rad] threshold of angle difference between the detected object and lane | -| `common.stop_line_margin` | double | [m] margin before stop line | -| `common.intersection_velocity` | double | [m/s] velocity profile for pass judge calculation | -| `common.intersection_max_accel` | double | [m/s^2] acceleration profile for pass judge calculation | -| `common.stop_overshoot_margin` | double | [m] margin for the overshoot from stopline | -| `stuck_vehicle.stuck_vehicle_detect_dist` | double | [m] length toward from the exit of intersection for stuck vehicle detection | -| `stuck_vehicle.stuck_vehicle_vel_thr` | double | [m/s] velocity threshold for stuck vehicle detection | -| `collision_detection.state_transit_margin_time` | double | [m] time margin to change state | -| `collision_detection.min_predicted_path_confidence` | double | [-] minimum confidence value of predicted path to use for collision detection | -| `collision_detection.collision_start_margin_time` | double | [s] time margin for the beginning of collision with upcoming vehicle | -| `collision_detection.collision_end_margin_time` | double | [s] time margin for the finish of collision with upcoming vehicle | -| `collision_detection.keep_detection_vel_thr` | double | [m/s] ego velocity threshold for continuing collision detection before pass judge line | -| `occlusion.occlusion_attention_area_length` | double | [m] the length of attention are for occlusion detection | -| `occlusion.enable_creeping` | bool | [-] flag to insert `occlusion_creep_velocity` while peeking to intersection occlusion stopline | -| `occlusion.peeking_offset` | double | [m] the offset of the front of the vehicle into the attention area for peeking to occlusion | -| `occlusion.min_vehicle_brake_for_rss` | double | [m/s] assumed minimum brake of the vehicle running from behind the occlusion | -| `occlusion.max_vehicle_velocity_for_rss` | double | [m/s] assumed maximum velocity of the vehicle running from behind the occlusion | - -#### For developers only - -| Parameter | Type | Description | -| ------------------------------ | ------ | ---------------------------------------------------------------------- | -| `common.path_interpolation_ds` | double | [m] path interpolation interval | -| `occlusion.denoise_kernel` | double | [m] the window size of morphology process for clearing noisy occlusion | - -### How to turn parameters +`TargetObject` holds the object, its belonging lane and corresponding stopline information. -WIP +```plantuml +@startuml +entity TargetObject { + * object: PredictedObject + detected object + -- + * attention_lanelet: ConstLanelet + belonging lanelet instance + -- + * stopline: ConstLineString3d + reachable stopline of attention_lanelet +} +@enduml +``` + +## Module Parameters + +### common + +| Parameter | Type | Description | +| --------------------------------- | ------ | ------------------------------------------------------------------------ | +| `.attention_area_length` | double | [m] range for object detection | +| `.attention_area_margin` | double | [m] margin for expanding attention area width | +| `.attention_area_angle_threshold` | double | [rad] threshold of angle difference between the detected object and lane | +| `.use_intersection_area` | bool | [-] flag to use intersection_area for collision detection | +| `.default_stopline_margin` | double | [m] margin before_stop_line | +| `.stopline_overshoot_margin` | double | [m] margin for the overshoot from stopline | +| `.max_accel` | double | [m/ss] max acceleration for stop | +| `.max_jerk` | double | [m/sss] max jerk for stop | +| `.delay_response_time` | double | [s] action delay before stop | + +### stuck_vehicle/yield_stuck + +| Parameter | Type | Description | +| ------------------------------------------------ | ------ | ---------------------------------------------------------------------------- | +| `stuck_vehicle.turn_direction` | - | [-] turn_direction specifier for stuck vehicle detection | +| `stuck_vehicle.stuck_vehicle_detect_dist` | double | [m] length toward from the exit of intersection for stuck vehicle detection | +| `stuck_vehicle.stuck_vehicle_velocity_threshold` | double | [m/s] velocity threshold for stuck vehicle detection | +| `yield_stuck.distance_threshold` | double | [m/s] distance threshold of yield stuck vehicle from ego path along the lane | + +### collision_detection + +| Parameter | Type | Description | +| --------------------------------------------- | ------ | ------------------------------------------------------------------------------------ | +| `.consider_wrong_direction_vehicle` | bool | [-] flag to detect objects in the wrong direction | +| `.collision_detection_hold_time` | double | [s] hold time of collision detection | +| `.min_predicted_path_confidence` | double | [-] minimum confidence value of predicted path to use for collision detection | +| `.keep_detection_velocity_threshold` | double | [s] ego velocity threshold for continuing collision detection before pass judge line | +| `.velocity_profile.use_upstream` | bool | [-] flag to use velocity profile planned by upstream modules | +| `.velocity_profile.minimum_upstream_velocity` | double | [m/s] minimum velocity of upstream velocity profile to avoid zero division | +| `.velocity_profile.default_velocity` | double | [m/s] constant velocity profile when use_upstream is false | +| `.velocity_profile.minimum_default_velocity` | double | [m/s] minimum velocity of default velocity profile to avoid zero division | +| `.yield_on_green_traffic_light` | - | [-] [description](#yield-on-green) | +| `.ignore_amber_traffic_light` | - | [-] [description](#skip-on-amber) | +| `.ignore_on_red_traffic_light` | - | [-] [description](#skip-on-red) | + +### occlusion + +| Parameter | Type | Description | +| ---------------------------------------------- | -------- | ------------------------------------------------------------------------------------------- | +| `.enable` | bool | [-] flag to calculate occlusion detection | +| `.occlusion_attention_area_length` | double | [m] the length of attention are for occlusion detection | +| `.free_space_max` | int | [-] maximum value of occupancy grid cell to treat at occluded | +| `.occupied_min` | int | [-] minimum value of occupancy grid cell to treat at occluded | +| `.denoise_kernel` | double | [m] morphology window size for preprocessing raw occupancy grid | +| `.attention_lane_crop_curvature_threshold` | double | [m] curvature threshold for trimming curved part of the lane | +| `.attention_lane_crop_curvature_ds` | double | [m] discretization interval of centerline for lane curvature calculation | +| `.creep_during_peeking.enable` | bool | [-] flag to insert `creep_velocity` while peeking to intersection occlusion stopline | +| `.creep_during_peeking.creep_velocity` | double | [m/s] the command velocity while peeking to intersection occlusion stopline | +| `.peeking_offset` | double | [m] the offset of the front of the vehicle into the attention area for peeking to occlusion | +| `.occlusion_required_clearance_distance` | double | [m] threshold for the distance to nearest occlusion cell from ego path | +| `.possible_object_bbox` | [double] | [m] minimum bounding box size for checking if occlusion polygon is small enough | +| `.ignore_parked_vehicle_speed_threshold` | double | [m/s] velocity threshold for checking parked vehicle | +| `.occlusion_detection_hold_time` | double | [s] hold time of occlusion detection | +| `.temporal_stop_time_before_peeking` | double | [s] temporal stop duration at the default_stop_line before starting peeking | +| `.temporal_stop_before_attention_area` | bool | [-] flag to temporarily stop at first_attention_stopline before peeking into attention_area | +| `.creep_velocity_without_traffic_light` | double | [m/s] creep velocity to occlusion_wo_tl_pass_judge_line | +| `.static_occlusion_with_traffic_light_timeout` | double | [s] the timeout duration for ignoring static occlusion at intersection with traffic light | + +## Trouble shooting + +### Intersection module stops against unrelated vehicles + +In this case, first visualize `/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/intersection` topic and check the `attention_area` polygon. Intersection module performs collision checking for vehicles running on this polygon, so if it extends to unintended lanes, it needs to have [RightOfWay tag](#how-towhy-set-rightofway-tag). + +By lowering `common.attention_area_length` you can check which lanes are conflicting with the intersection lane. Then set part of the conflicting lanes as the yield_lane. + +### The stop line of intersection is chattering + +The parameter `collision_detection.collision_detection_hold_time` suppresses the chattering by keeping UNSAFE decision for this duration until SAFE decision is finally made. The role of this parameter is to account for unstable detection/tracking of objects. By increasing this value you can suppress the chattering. However it could elongate the stopping duration excessively. + +If the chattering arises from the acceleration/deceleration of target vehicles, increase `collision_detection.collision_detection.collision_end_margin_time` and/or `collision_detection.collision_detection.collision_end_margin_time`. + +### The stop line is released too fast/slow + +If the intersection wall appears too fast, or ego tends to stop too conservatively for upcoming vehicles, lower the parameter `collision_detection.collision_detection.collision_start_margin_time`. If it lasts too long after the target vehicle passed, then lower the parameter `collision_detection.collision_detection.collision_end_margin_time`. + +### Ego suddenly stops at intersection with traffic light + +If the traffic light color changed from AMBER/RED to UNKNOWN, the intersection module works in the GREEN color mode. So collision and occlusion are likely to be detected again. + +### Occlusion is detected overly + +You can check which areas are detected as occlusion by visualizing `/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/intersection/occlusion_polygons`. + +If you do not want to detect / do want to ignore occlusion far from ego or lower the computational cost of occlusion detection, `occlusion.occlusion_attention_area_length` should be set to lower value. + +If you want to care the occlusion nearby ego more cautiously, set `occlusion.occlusion_required_clearance_distance` to a larger value. Then ego will approach the occlusion_peeking_stopline more closely to assure more clear FOV. + +`occlusion.possible_object_bbox` is used for checking if detected occlusion area is small enough that no vehicles larger than this size can exist inside. By decreasing this size ego will ignore small occluded area. + +#### occupancy grid map tuning + +Refer to the document of [probabilistic_occupancy_grid_map](https://autowarefoundation.github.io/autoware.universe/main/perception/probabilistic_occupancy_grid_map/) for details. If occlusion tends to be detected at apparently free space, increase `occlusion.free_space_max` to ignore them. + +#### in simple_planning_simulator + +intersection_occlusion feature is **not recommended** for use in planning_simulator because the laserscan_based_occupancy_grid_map generates unnatural UNKNOWN cells in 2D manner: + +- all the cells behind pedestrians are UNKNOWN +- no ground point clouds are generated + +Also many users do not set traffic light information frequently although it is very critical for intersection_occlusion (and in real traffic environment too). + +For these reasons, `occlusion.enable` is false by default. + +#### on real vehicle / in end-to-end simulator + +On real vehicle or in end-to-end simulator like [AWSIM](https://tier4.github.io/AWSIM/) the following pointcloud_based_occupancy_grid_map configuration is highly recommended: + +```yaml +scan_origin_frame: "velodyne_top" + +grid_map_type: "OccupancyGridMapProjectiveBlindSpot" +OccupancyGridMapProjectiveBlindSpot: + projection_dz_threshold: 0.01 # [m] for avoiding null division + obstacle_separation_threshold: 1.0 # [m] fill the interval between obstacles with unknown for this length +``` + +You should set the top lidar link as the `scan_origin_frame`. In the example it is `velodyne_top`. The method `OccupancyGridMapProjectiveBlindSpot` estimates the FOV by running projective ray-tracing from `scan_origin` to obstacle or up to the ground and filling the cells on the "shadow" of the object as UNKNOWN. -### Flowchart +## Flowchart WIP @@ -305,9 +578,9 @@ stop ### Role -When an ego vehicle enters a public road from a private road (e.g. a parking lot), it needs to face and stop before entering the public road to make sure it is safe. +When an ego enters a public road from a private road (e.g. a parking lot), it needs to face and stop before entering the public road to make sure it is safe. -This module is activated when there is an intersection at the private area from which the vehicle enters the public road. The stop line is generated both when the goal is in the intersection lane and when the path goes beyond the intersection lane. The basic behavior is the same as the intersection module, but the ego vehicle must stop once at the stop line. +This module is activated when there is an intersection at the private area from which the vehicle enters the public road. The stop line is generated both when the goal is in the intersection lane and when the path goes beyond the intersection lane. The basic behavior is the same as the intersection module, but ego must stop once at the stop line. ![merge-from-private](docs/merge_from_private.png) @@ -326,4 +599,4 @@ This module is activated when the following conditions are met: ### Known Issue -If ego vehicle go over the stop line for a certain distance, then ego vehicle will not transit from STOP. +If ego go over the stop line for a certain distance, then it will not transit from STOP. diff --git a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml index 22f68733a3bc2..1e6ce843de528 100644 --- a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml +++ b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml @@ -2,42 +2,47 @@ ros__parameters: intersection: common: - attention_area_margin: 0.75 # [m] - attention_area_length: 200.0 # [m] - attention_area_angle_threshold: 0.785 # [rad] - stop_line_margin: 3.0 - intersection_velocity: 2.778 # 2.778m/s = 10.0km/h - intersection_max_accel: 0.5 # m/ss - stop_overshoot_margin: 0.5 # [m] overshoot margin for stuck, collision detection + attention_area_length: 200.0 + attention_area_margin: 0.75 + attention_area_angle_threshold: 0.785 use_intersection_area: false - path_interpolation_ds: 0.1 # [m] - consider_wrong_direction_vehicle: false + default_stopline_margin: 3.0 + stopline_overshoot_margin: 0.5 + path_interpolation_ds: 0.1 max_accel: -2.8 max_jerk: -5.0 delay_response_time: 0.5 + stuck_vehicle: turn_direction: left: true right: true straight: true - use_stuck_stopline: true # stopline generated before the first conflicting area - stuck_vehicle_detect_dist: 5.0 # this should be the length between cars when they are stopped. The actual stuck vehicle detection length will be this value + vehicle_length. - stuck_vehicle_vel_thr: 0.833 # 0.833m/s = 3.0km/h - # enable_front_car_decel_prediction: false # By default this feature is disabled - # assumed_front_car_decel: 1.0 # [m/ss] the expected deceleration of front car when front car as well as ego are turning - timeout_private_area: 3.0 # [s] cancel stuck vehicle stop in private area - enable_private_area_stuck_disregard: false #In the intersections which labeled as "private area", the obstacle vehicles judged as "stuck" are neglected if this param is set as true. - yield_stuck: - turn_direction: - left: true - right: false - straight: false - distance_thr: 1.0 # [m] + use_stuck_stopline: true + stuck_vehicle_detect_dist: 5.0 + stuck_vehicle_velocity_threshold: 0.833 + # enable_front_car_decel_prediction: false + # assumed_front_car_decel: 1.0 + timeout_private_area: 3.0 + enable_private_area_stuck_disregard: false + + yield_stuck: + turn_direction: + left: true + right: false + straight: false + distance_threshold: 1.0 collision_detection: - state_transit_margin_time: 0.5 + consider_wrong_direction_vehicle: false + collision_detection_hold_time: 0.5 min_predicted_path_confidence: 0.05 - minimum_ego_predicted_velocity: 1.388 # [m/s] + keep_detection_velocity_threshold: 0.833 + velocity_profile: + use_upstream: true + minimum_upstream_velocity: 0.01 + default_velocity: 2.778 + minimum_default_velocity: 1.388 fully_prioritized: collision_start_margin_time: 2.0 collision_end_margin_time: 0.0 @@ -45,52 +50,46 @@ collision_start_margin_time: 3.0 collision_end_margin_time: 2.0 not_prioritized: - collision_start_margin_time: 3.0 # [s] this + state_transit_margin_time should be higher to account for collision with fast/accelerating object - collision_end_margin_time: 2.0 # [s] this + state_transit_margin_time should be higher to account for collision with slow/decelerating object - keep_detection_vel_thr: 0.833 # == 3.0km/h. keep detection if ego is ego.vel < keep_detection_vel_thr - use_upstream_velocity: true # flag to use the planned velocity profile from the upstream module - minimum_upstream_velocity: 0.01 # [m/s] minimum velocity to avoid null division for the stop line from the upstream velocity + collision_start_margin_time: 3.0 + collision_end_margin_time: 2.0 yield_on_green_traffic_light: distance_to_assigned_lanelet_start: 10.0 duration: 3.0 - object_dist_to_stopline: 10.0 # [m] + object_dist_to_stopline: 10.0 ignore_on_amber_traffic_light: - object_expected_deceleration: 2.0 # [m/ss] + object_expected_deceleration: 2.0 ignore_on_red_traffic_light: object_margin_to_path: 2.0 occlusion: enable: false - occlusion_attention_area_length: 70.0 # [m] - enable_creeping: false # flag to use the creep velocity when reaching occlusion limit stop line - occlusion_creep_velocity: 0.8333 # the creep velocity to occlusion limit stop line - peeking_offset: -0.5 # [m] offset for peeking into detection area + occlusion_attention_area_length: 70.0 free_space_max: 43 occupied_min: 58 - do_dp: true - before_creep_stop_time: 0.1 # [s] - min_vehicle_brake_for_rss: -2.5 # [m/s^2] - max_vehicle_velocity_for_rss: 16.66 # [m/s] == 60kmph - denoise_kernel: 1.0 # [m] - possible_object_bbox: [1.5, 2.5] # [m x m] - ignore_parked_vehicle_speed_threshold: 0.8333 # == 3.0km/h - stop_release_margin_time: 1.5 # [s] - temporal_stop_before_attention_area: false - absence_traffic_light: - creep_velocity: 1.388 # [m/s] - maximum_peeking_distance: 6.0 # [m] + denoise_kernel: 1.0 attention_lane_crop_curvature_threshold: 0.25 attention_lane_curvature_calculation_ds: 0.5 + creep_during_peeking: + enable: false + creep_velocity: 0.8333 + peeking_offset: -0.5 + occlusion_required_clearance_distance: 55 + possible_object_bbox: [1.5, 2.5] + ignore_parked_vehicle_speed_threshold: 0.8333 + occlusion_detection_hold_time: 1.5 + temporal_stop_time_before_peeking: 0.1 + temporal_stop_before_attention_area: false + creep_velocity_without_traffic_light: 1.388 static_occlusion_with_traffic_light_timeout: 0.5 debug: ttc: [0] enable_rtc: - intersection: false # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval + intersection: false intersection_to_occlusion: false merge_from_private: - stop_line_margin: 3.0 + stopline_margin: 3.0 stop_duration_sec: 1.0 stop_distance_threshold: 1.0 diff --git a/planning/behavior_velocity_intersection_module/docs/data-structure.drawio.svg b/planning/behavior_velocity_intersection_module/docs/data-structure.drawio.svg index ec5878a0d828e..028ec8b32836c 100644 --- a/planning/behavior_velocity_intersection_module/docs/data-structure.drawio.svg +++ b/planning/behavior_velocity_intersection_module/docs/data-structure.drawio.svg @@ -5,31 +5,31 @@ xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" version="1.1" - width="2382px" - height="2070px" - viewBox="-0.5 -0.5 2382 2070" - content="<mxfile host="Electron" modified="2023-11-12T05:07:41.048Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="NhhSyCkZKf7kn4cJ36_Z" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">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</diagram></mxfile>" + width="2515px" + height="2295px" + viewBox="-0.5 -0.5 2515 2295" + content="<mxfile host="Electron" modified="2023-11-14T02:56:49.728Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="TBnrjbXd8NQuLxVvVAEO" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">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</diagram></mxfile>" > - + - - - - - + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + - + - + - + - + - + - - - - - + + + + + - + - + - - - + + + - - - - + + + + - - + + - - + + - - + + - - + + - - + + - - + + - - - - - - - - - - - + transform="translate(292.95,0)scale(-1,1)translate(-292.95,0)rotate(90,292.95,832.55)" + pointer-events="none" + /> + + + + + + + + + + +
@@ -285,18 +285,18 @@
- closest_idx + closest_idx - - - + + +
@@ -307,21 +307,21 @@
- stuck_stop_line + stuck_stop_line - - - - - - + + + + + +
@@ -332,18 +332,18 @@
- default_stop_line + default_stop_line - - - + + +
@@ -354,18 +354,18 @@
- first_attention_stop_line + first_attention_stop_line - - - + + +
@@ -380,25 +380,25 @@
- occlusion_peeking... + occlusion_peeking... - - - - - - - - - - - - - - - + + + + + + + + + + + + + + - + - + - + - + - + - - - - - + + + + + - - + + - + - - - + + + - - - + + + - - + + - - + + - - + + - - + + - - + + - - + + - +
@@ -632,18 +640,18 @@
- next + next - - - + + +
@@ -656,18 +664,18 @@
- prev + prev - - - + + +
@@ -680,18 +688,18 @@
- ego_or_entry2exit + ego_or_entry2exit - - - + + +
@@ -704,15 +712,15 @@
- entry2ego + entry2ego - - + + -
+
@@ -722,7 +730,7 @@
- IntersectionStopLines + IntersectionStopLines @@ -730,7 +738,7 @@
@@ -741,28 +749,64 @@
- PathLanelets + PathLanelets + + + + + + + + + + + +
+
+
+ + + occlusion_wo_tl +
+ _pass_judge_line +
+
+
+
+
+
+
+ occlusion_wo_tl...
- - - - + + + + + + + + + + + + - - - - - + - - + + - - - + - + - + + + + + + - - - - + + + + + + + + + + + + + + + + + + + + + + - - + + + + + + + + + + + + + + + + + + - - - - - - + + + + + + + + + + + + + + + + + +
- - - occlusion_wo_tl -
- _pass_judge_line -
-
+ + object
- occlusion_wo_tl... + object
- - - +
- - closest_idx + + attention_lanelet
- closest_idx + attention_lanelet
- - - - - - +
- - stuck_stop_line + + + stopline, +
+ dist_to_stopline +
+
- stuck_stop_line + stopline,...
- - - + + + + + + +
- - default_stop_line + + object
- default_stop_line + object
- - - +
- - first_attention_stop_line + + attention_lanelet
- first_attention_stop_line + attention_lanelet
- - - +
- + - occlusion_peeking + stopline, +
+ dist_to_stopline
- _stop_line
- occlusion_peeking... + stopline,...
- - - - - + + + + + +
-
-
- - - occlusion_wo_tl -
- _pass_judge_line -
-
-
+
+
+ + TargetObject +
- occlusion_wo_tl... + TargetObject - - - - - - - - - diff --git a/planning/behavior_velocity_intersection_module/docs/intersection-attention.drawio.svg b/planning/behavior_velocity_intersection_module/docs/intersection-attention.drawio.svg index 57552f586e63b..94b63a97608ef 100644 --- a/planning/behavior_velocity_intersection_module/docs/intersection-attention.drawio.svg +++ b/planning/behavior_velocity_intersection_module/docs/intersection-attention.drawio.svg @@ -6,28 +6,28 @@ xmlns:xlink="http://www.w3.org/1999/xlink" version="1.1" width="3707px" - height="2195px" - viewBox="-0.5 -0.5 3707 2195" - content="<mxfile host="Electron" modified="2023-10-03T05:15:42.124Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="WBrLRHcQvF5FOJ4jcZAE" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">7V1bd+M2kv41Pmf2QTy4Xx7bfcl9JiedTif7kiNbsluJ2vLI6nT3/voFJYEiAQgEKYCEbCvZnViiQBH11YeqQqHqAr/8+OWb9fT+w0+r2Xx5gcDsywV+dYEQwoDiAqn/Kt/8unsTIsBgIXZv3q4Xs/3bhzfeLv5vvn8T7N/9tJjNHxoXblar5WZx33zzenV3N7/eNN6brterz83LblbL5l3vp7dz642319Olflc/RPn++8Vs82H3vkD88P6388XtB31vyOTuk49TffH+WR4+TGerz7W38OsL/HK9Wm12//Xxy8v5spxFPTO/vfyGfP3vu9mvL2b3b968fPXH/377ZrIb7E2Xr1SPtp7fbXoPffntX3fk6k9y+Zlfvpfz3ybo328mYv9s/0yXn/ZTtn/YzVc9h+vVp7vZvBwFXuDLzx8Wm/nb++l1+elnBR713ofNx+X+4+X0ar68nF7/fbv92svVcrXeDoPfbF/qkofNevX3vPYJ2L7UJzeru80eQ5ju/65d94rLy911i+VSv3+3ulPXX06Xi9s79ee1mqK5ev8ycM72c/vPfL2Zf6khaT+H38xXH+eb9Vd1yf7TCSQIk4LuvrdXjQmHYD/S5wPIsJ7dDzWAIf3mdA/t2+oWB+Gp/9jLr4MsteieZRkuSwYpMCWpuWsQSX78ZTX95urtHz/8yT7PFr8SxjcPEynbJVnKpJTXerWZbharcr4mEpw+WRUXT6/0rUDLJFLAaSEPL9GcUcoxVB8zCrEiVwSxNb0UkAJhjCjDmHIuqT3ZBMhC0MMYACeaeyHa576ctIVaZH4sFeTn1cNiL4Cr1Waz+qhkoC94sUfyZmWollpL7svBPn65Ldff4mr6sLgulNCUjtxdv14u1QI53+qXeuvF3e32zqAQDHEBMScAYqn+T10xv5sdPlfYxYwreUjOGSWyVKb1tV73QMG4oXF1TawjiQBLuffKuVJ0sdiUsqVutPkRHaybgjRR5NBKKKANFMhlKmQEaOWBX0E7vwYIYnQxQN4uBySwLQeWjBw7mSzdxXC5/cfFrCGCUOo8W8wPS93+qmTymRjyUUuVvXpxMaR8YLt8StIqrfvDBNXk0RSeZWFUarL7RJMbsWUx/7LY/L4ftPzvP7YcSPd/vfqyv8P2j6/6jzs1B7/X/6h9q/zz8LXtX4fvzd4syol61UMdH1af1tfzAOpRq8Ht3DeivnA+a/hFNnwaq6+NDv3eer5UOvBP08dyQWZ/h59XC/XEFToJRQ10YtIcYffg+y/VfRdzHNAcRxluzYF2E2MNtAVw9dQnYDrAtK5h+no5fVDreWJYgwIx1IA2EjwNuNUgP8/XCzWNpT2eBuIiEOKa/zOBuHIHG9CEoifGpTGOqSupIY7bIX79af1P5TwOy+GgE4cPwcW54E/buxo3tB/8IOSNcUwz+gj8FASmX2uX3ZcXPPjUxflzj/4q1LwctVxuPASWhqrsfm5UxREBiuNw1s3Yh60Vrk8M7bhRfuK3e5WzcZ7c7yfAcA4oY/uFuQ5+Rmz0M1lID9ZPc9RomtW6TlPBIgqkH42iTFgFF4gQIjigjDJO9eKg1aonx1CG63GipmrjYU06DdQQtS3V7DetszWVq3uIUIwUfCPAH3wjtkZCQFwee0KVZLx9tmPHTiaY6UB07crdy6XBlePfT4MrQAX77gTYsRQ2uGQC4p2DkWVfB6WjiFp9DA3XTNgYAmzYNT0J2GAHc5jElAtB8L7G4DRKJG1sUhjxBsokK1mWYgmAIlk7yEalQ/6YkUKI6ltcGGtcNC2GIMAKfVTbFs4wbextiwNig0kdswIf9qlMIGFe2+gSgOz9mRF3NaC24YeMp48vJoiUnJgtG0scRNmsTgcmVfwcggD35Vw3OHpIalISM8dEMIEBVxwKmmJDkBaUHjhW2jJEWBR67R9IhgHexSkBtEqGiQJo2gxTax43TDFSvRG0FbL9rGfwuEJLa1CuUppW0666MhPbjgPfekHKDLb6gtHP7vPfBCr1aK5KA5uFAc5htNBzB80ZciswDdTJGUEdEuBFYXAgG3lvI0wLLAjrXcPc/kcVzidNGqWGIJGfP/yiBJPEBrooIDlTBSRYNmHZNKRMVPYMMjC/mptrTbIYhDNJNnizZvAIBGPKdaxNTWPWJlw5xwU5xCf2wKpn+cjG1yF2BBKxYNGzKP/93Wr2hfzzYUEu362/+5v/ya++ncCnFo5wBqDVBLt4csblVdhWkRfCXUISTWA0d+0gB8WQYQg3YBJHIZzycTi9I4hnwlDBGeMEM6bsfVHtoWr5AJd8EHPIJ4ZD6xZP4piEW31EFvIpQ0UuYtXLppAu8XDHMp5OPInDDWlzLrsJrm6feakkE6OLe9EDedHXzPKjkloDx7Os3NM+pBffAZAt3rgPapkgqLOkw11l78jYBmck99j/RIf7xnKJ3YBN7xF3gWmsnW8foOseq3edzwT53QEaCn01pFepcEL6nP786vL3P8D9j8vJh3e/bNYvrz7KEMf0FANLMo5fsDADq7x2ykIMrGjHMKWxFzdhXNp5S0SvMQmSY96hf14yPlvBW0L/pr9/+Iku3qcWyvGEz8rGrYlLBtm88UQCScFMqQhKC2xvsDGdvF4XDIeFT+NDBXPF7pffff/7jzOymixevf/++//wVxOMnrJklMdhHsvbSsaRTaAkU0DH1mck4TifqVv6rW37NRdL3HkyM1m8lEWMMTDF1HcLr5Q7MkbjkBkBvEj2metm6qfjqEaZU4SnOrKPGTtEoHjYYZAZvyoldsg+mpgUOwEO6NPADoPQ2D5QytvTUFajUWRuRkBmsFg87FDErZ9O0mOnmy8Ygp3Z9OFDFeuw90rflP+cMcSYJqMDoSiXivcGmT0eS7c16J7iAGv/qfCHg8Bxb9FSZLoRCdce+2Zq7SnoABSCA7Lb2+JJDdIo8fB2/93VevNhdbu6my5fH969nC+vtmPpnVKLafYgbbpCjweVDBs7KuGopEJYoyFjtHiotH86ZqD7LzS+dDKOnZGoxGVuXOnHMtFBrVguN8eWKLjj8BYEEBTUkXfBUWFaTNFiVIkjIecpLl2NLz9xxXdSHruhaVboY4wY43SwRaC0Rwtj/R706gRAyD7po470m5FLpt+pR/r1pKSI9K/Ez/9Mv75/dfvy9b9f/Rf+NpncBuUfjZUYKC1vvtouqbMZK8/B2LOmWK4AGEqk/hWY6/pg8WcwdilZA9dX02sxcy4wCBNCZ07Y+mXdjltrfoF+QUf6FS1nOtX0hpRVqzIeW6Z2+nC/q7Z8s/hSisOcawDE1L39AQDlwLH832xfSWRQ7QUXhFFCy4oGWNnqTTdPFhAiYtWWqOfHokKAMr2OEwShDmY302Pdl8SXZYDNFkeWe/vBtgqApC4xVuV7k4mR4QIiCSmAlEConPMzFmNIwCitGFGt2vKw2ghJQcskYUGFUk0E4XnI0WWR0dHVkW1fOcgRNcTIYAEFqhY9aO8vZyRG0ilwcSYGSFUBhBWSVEYcJM1NEmqYeMAWFOGFdOQBUJBIGnRccpzNb6aflpsMVAoaDg+VBcMHnWIoZ52iAbkc+hTOzXL+ZR+3uOyWN6mfnRcISAzU01EqoPJOdyPpNgKFBMoCVEYD4hIwyXcH0Wc6FgIVWUFlU1ClAIpShaDdpZxJ2EM9RCEROLyatFyW2++5HQNJ15FTp40H0MTQx1KHKBhtA9MXR6gfevAF7esJvr7rMsH5BCo1tTYHOeqH7XI0K4+0MmkGwnOILfmM5zqefbsadTz7rssHz1ySQuoOJrXcCF4QTgx3qAfAncNzBfwCmBk+iYHeLVtioJLofYB+cj2BUKB7M5nrSPdemBHUETFxCPtniXBoohqYu/uJER2wBfCM6Hbqdpw18l2XEZ4BLBizuJWKguODwdw/j9I5vloaUAGS1T52Aj1RfWzXJuQjsVF8R7Zabe7cgF6i2QAhx72Jm1u5TRyBYYm726GBYfB8hsStMxNamRvmVR55UkaEmuc3J4zI/kSNkDkaJQMfpg8Ii4yUjqC0G5mzI5G/wWNYbSIevTaR22UMSFR4VLWJXCl81Ka50BK8fsB26Cxo9H/g9bJhlfgHKUnkxklAKCdJZuW4YjHaciDUKpdkpYjcYkl8KPuUetXBxZEjCWtbYcxUIse5eeBYfJMVIzr1KNWo4c+OomqPY+YVtcGGrY7LnMraym024Qk1mszDqhD5x01sPgVkAoxSUNhfisiLtFwA1FHQwfVYeHPcFlxGOpljPg2Pe7zGLdAA83O4HaJokRQveNu3cfKKkXREY/jmu6E8ZFSWxPELdTzysyicWmWKdPJgn3iwORpXMBgWAfHLbTxuBHCMzfIE1vmhLukK3BoND4yAp34ayVJoHdwcqO6YWyqJz+BmLxXzjBilDqnoSRlKKiS95fbY9hm86G6tRqkvzIb+XfsM0DhQd9I+A2HGaKlTHnLeZ5BlR0YBuPq3KnR2MJU4qX2K7KCXerdgorpAF8xrFsFrXMKMPZ54ZSRHKKkQ3tHNFq0fKuF9B2RZQfIwvUbaGqSg4Lz62MHwmMqCO2LLPFVsOYThx9sa4gILyhmhBAEMibU1hDgq++RxLDHlkppbQ0gEIkcR5tjQgYAWBBCAJcBUQLM4FASkoEDqj6GwT5BTNYJu09pcC3jBeCr8BNBpdEXftbkeVVwTI7BBCSwotPVZsoIk0md3MvapEY5H0vHKK+b2hD6Hvea9MBN7jVJWNxFE09eGUBYCHZafnjnZtGmHGDchjQ+pNIgn9VmEgPDOGPsgWhcKBGhDH6CQfo1Qf5i9RPtqSa/dmGCd0YTYqjMkrxAXFdIDZ8xxFJ3BvpsQ5L1JpK0fSry/Qbh+w7HnIdQ3FnVOWtI9JtStylSee0z9MoO1UsMUSh26nZWZUmPkwyejUZSa+3WA9dDpaFEOlFwdHlvCu3ezoD1wl1uCMMda5IedFgEOJ+n6VJKzClU7R4wH7ZefXr+7//x68oG+/OvPn7+8ff3+fy8nroAFq+oeNCDO/vtppT+YPGzP1L9QF2B6/2ULFf25+q/b/f9uB7rSb7xbX03vylDeevXwsF5NZw9bCSoBKkispzc3SmcQWG7Ft/+ueqYra7x1wDv6jX/9OL/ZTD5M72aHm/zP8e8F3s85L1fT679vt2o+ud4pdjk9i7vFZrGtrHt8hk6YanBdccjhTcyuxfzqxr7h/HZVzvBUmeaHB97dvfpF049lDOHu6mEbSpiWMrpfL1brkoIQWCmnvpzJD3Pz0o6TmvsU7retjqO6esyvi/lytp/Wh+PzGk2pGrN+q1jtTgvkmBb5NGZHjau7Us57Lfm0vpvMFuv59TZCdBB/0fJwLjkfufThfssE7fMAQsmlG/zUe7ufoN82VvPN/MumuX5P99HYpeKTCztI+3Exm21Laq/n6tfvdynKJXTvR6hR6eUFfVWO9Gmz2j2hI8dh7zY76tN0W4s7lbulsJmzPeHEEX2ryls3Tl3ICLE358qUuGOsMxTacQv7oCTqhvOHTVIpUWIXJXbErWHV2zvBtrZTUPFbX3SbxGyMRJeEzFkPNxCJlMZoHJrVtqIVmLdvpn563GRWJ3a6tTx43NgxHQyiS3v1wo45GgxMDOuFHeunRw5SObHTMRH6EYOHQGEmgpxCPFRayRLpiIda4BmEeILKIT9nrtYEJZBhJDJIcP+GTY7xmK5rPFDsI6iM8hMhEGv5J33juFudNkeDZtn4mARi/3QRu2GTGz8RSlg9N2zqhEohe2dLYkmt0UQyVNo/ne27IHb6hcaXEuE4oHBVlGbI/oPq9ebIozraSMrCytMVBBSuLFFXdd1I/X/cwkocFzk7YSFYWGnQAisJuoTlSuJNKazn81EdKZ8jmwJ7l5YiVWWJ2mgD25hncD5qWIUFwCqOhF2Hc1wlJxJGMQdIeelevTHvPX6vMVHf4/demA/3SGruyMMTnCAJzNEQSJa24oZ0t8j8M6RbTK52SNPcIC0YLaQ060bXIjgkSlnplvtwSGnK+tJOYeBuEb7nSur+fdhW8OeGfWVVWFtaZoPmDu2eLYeeQ5EsG98N6G7hyufjwy0meTud55aFSDAxD7YTfbKtj3ckrWPy2BgtMaRD2gM9+8cN/5iaMuPmxm4HBFijqZU6WQ0hNwKeIySdEwXMbr4M9d+Fk8QebWAEPEdIrAiJpeOOqqkEOdrxpYyQ0AB38qkJygxlMeionjp0KEsHLZ4NxRM9nz3g210fkdki4TIU+zcecRiKhA7rzLP00dnHdgLLu9i2Qzo334diMyuNMcZPOYFFoLRsH9eIiaEtAth6V0LJ3pM9cW3rUVWJcEBrrRi4OYOUkYL4WjlQ6EBJit4NzskOKbDy6Hs3lGVkwwq+BJlTflQH21OkGV/DQ/ZvcGMlIN42VqOAIQUDcatksBZC7AYBbsGM0MEhvBzakR4OQ0psYlS7Q8jeYK+KJg0iMh4hVbIp0vKgoG7sbW9AYktYdbnGKjDRKBZxqErDgWhYhqXGdK1K0xEbrYafq/SEl/UyMfyQ0WoOmiWQgjtMGCXZ05VScitAQI5l6lJK2KE2R1Wh4BA11aFcodsUQv1l1Vc6VGvCzWpNiHXXi7aqS0NpSV5hYdbENu+pIxAaymYGliPlR5vdEbihcQlynPk4lfxCVK6mH8zQD9RDP2KFzobSpLw6dxiapPzdSKo08HojAwyufKIKFHGrefe2LmKEnpAIVoOYdBbNvMUBq/ujDytMBggrVLDu0CbSqBqt/x4vsBDSNye2/+raRxtfOM1tBSRt0STrDemWTEA2wmgtO6MHFnook5EEB7V3NlpgQac/5WvXjbNL5BV4q/Wm9aDVetMXZmK9IWCQvVmpPbidIG0OhOCw5pvo5q5ETF5OhuxGrCwXnIcmN+O8sptNnGPQE+fMGGdgL0UEbOvnEBU7JYeljKTRJswRQS1Ad0fS+sS+EnB+Xge3EDGoum+EGBn9ZbDp+8dqGguN+6AB4l8ywENNs2dW6lbtwt3Lq5/jnieHdlleO6dPGb6yoAMf/ZcRjII+a/cIW2vdBNzKbRr9rdwm8+I254F4hbF+BKdGY9aZqKqw9VCByRFc7LMkIkhMUTHhCF2NQkSjtYfotIXZjXL6MGNsmgo1wWRebndJLGalDQ7ICTQFrdFkMppyd0AJsJdGamyp7BFYgENzO4MlhBSFlFVvO2RzBqegkKL6vi7+XAeGwOqS2sHwCKHwy2//uiNXf5LLz/zyvZz/NkH/PkxL91n2S+3kaYYFxGqiBeZqAWaQATyfODahzKl09HlOMJXOnjEh5VBPWVjZS/F6e3CutTBUdWVr+0AvJsIXS6qkxahkQJbtdLnhX6mVtODUpxBYkEK/PUif0JDqoyP2CaUX5hYhCuoG6oLIhNjNQEfAiNEQFNFm33ajISjSJ3rGbggaUqI0tlIfO3M3tMiUIOrLnGESBEgMCwcdp+sVGqDT0WKZlSw6NEuE0miWKIdLL2oLXfoQ09pWTSOjta2a1qZMzGalZw2A63rvOpC57QporVudw5rYfxfQvEuioGfZrNvzK6B0/oq0TQ4DuPVEL7a7mg6xW9zW5PA0ZUTnqYwKeU2ANvHJ/FoSqoyEeO8Ce+liLIXQjmCqXIqhtEGvdAeNKPNWemy4xVaN0J6+ekHLRDUgkg3QGrWROQIx1iloqIZxF+xfDeOpxv3b//w+f/Hd++9/+O5vePlu9e3tPz852yRGNMODm1F1ygxLZpjryJ6mLYEKV4ESAAvpcJgUlZqFMPsY4U45pV/Sz7NvcShv+cBfpy3fdZmwllSEQWAVFTK6jSgQFxQC/SnjPfsKUIbLypZ6HNzpJolJa4xjsieTVn2T7a5sgpEyKGTIizgL/BeODGQMcWHmmUQjsYCth+FJrKvD3ytlqj+JZUI6ClIFqMX6jR7PBBlbssFOvH9cjrmCI6heRvmMeDzjFEHAbrA+auTYQh//9BGjxCwtw4Wd2K6uK6hjlwCC0vyBEql/BeZmp6Noe2Wdyq/BznR+Nb0WM2c+hFrGCJ0FicqLj2BeRk232MHKO1lUeIcOiqawiFFGxvlEIY5ytb3SIobpw71Cq/rjZvGlFJ2r968lEmVycOBIarnZvgYUldm9T8cQ6mF4VAiASvOHIKjsA9c5Pfcl8bebQ1pGJhXcJZDUJbgdjscTnK7xkqncQmq5R5GbEsWbN0cTw9BeSJlpnXCcjs1IeCFOeVKlY9tXBnIj4Jzk1sl/PGuDQx9p0OY0seRClIHtqLdr9sWNN/khTmA6pZnNb6aflpscVKa57Z+5ygRk6OusnJvl/Mveh7/s5s7rZ+cFAhID9XSUCogl242kc2MLCQij5VYrl4BJzncfa2cfwgJCAiFVHouiSCFoZylm4nTTZhFK0dPHNoaB0BgnsRft7BXItjp41UAQ+++n1S73vPZft/v/rXR26whrtT1cuE16VwpsfXd+u1JfWU4VGexHUU+xG6g5uHr76vDeKevBssxsu5xe/327/VrDBCtfrqWhfG0/qWeBU5unqsZUDqqzQR4raZ8Bq+0r1pkO9SPy2BFGiHFE3g2s9Nn6oVKprusTHmzGKt1sFZp+79XATGhN/R4omAGnaj3snlXPODCcdYapMVpqjnPFsOJzHL8BwMVxXxfz5ewcWI6/AeCsWE5SO146MMulb3pQScVmohY5Vd/sw3uxWS63ZgUM2n2ouGGhd2A5Yuz0lk05jHSDxCyHXFHGbiw33WyUtEv3ymKrEWnpQDdZ0hI0++ZwgB20lKqilBsLIZHLJD1YA2ip+mYGtITyyh5RcEJWoy3Zt7BqucdokZyAwxpfyBXPazem9jsTRw2xio+uV3c3y8X1ZnF3u2etBzdtHTG8DK1Qer9p6oEzq8RBMdP9gahrhcwyl9M6KfVxMZstj8XNmtp2hCb1zQP1KyXpoWZMuTwq69rLcXXdSEZ6AVvVWWcEEGY176aOWR07IwAF2Lx5RugrhDyenAA8+t5yqqSA7sI6r6yAoE7hZ5kVcLLk8k4LCOqIfb5pASdLL+/NMhywv3yeeQHdBXdWiQEh1c4fi9mRX2ZASPXwc8wM6KE055QaEFJa/DGkBqC8wsuPIzcAR0uxn4zkUXPArLqa4JgPZ6NhKI8aZ5Vkf0xYfoyER49Mn9pRXnBkn/qsEu0Ti8tc7hwFb/JZ7sjo0ZAuPvWwksN5S+78cu2HFV+Vm5up/AYLisRwqxOLzuwZn7nossq4TywaYeyH6mcd0bUmZ5R0n1pxmpHE3BXnieTd47wS76GRIQF7FtEwx6mOjA3kXpOA2IyjWea+2IUtu+QH1pkwU1MIs6Nfx51pOIgzTQKiFgMuZ8ek5YdEO2N+bepUPt4zCQhmRLPkARDTWhZaXxc6lZCqUmbNjRaa9cY0GT380cmJTiw7fk6io+PHP7o40KnVTpyT6EZPB+nkQA8rOp615AJCH4/A4NCf2rk5QzvMdNwUjm4O87CKkjfFBQQ6HoO/TPI60UmbFkzviu7+YRI7yzR4L3pwv5hIpUAECMDVvwpPzT4wEw4pKwCvHDKbPzlxCL+sb4xoVXxPRFBKZ1MvFmB3pOmMF1KuM6j5nR8w4RvTWBbb6MQuQMGMMp2QkEIcBCKpnUdQVovmDnc7RvcPt/ACTI+8OvpwxDERHEtMuQxq7+MCkKO7z/j4MZr9YGNphkCUNKDL8lJiG7Wpm/24MTRGwV7McmQAhcnC2HalSuuBw/0QqND+5CCazhN3SRiv86UiCkAumi2C5EXXFkEdMdHaFFMza2tTTL1+ZmLsQWW41mwRYtRMEKRuioC+B94hM+7SuAn23yRxq18REAOL1hErgtr0LXGt1IY11AZ1Vppe/bESqBDOS4WoD9yEGujup0GY+G5CTRUK0qDO3bF6/IZYvbHcqpu+bMEJCpt7r6xwxcTnqZhY+vDKYBTFJH6lYH0UM1oQJPiE+/BBEM6MpDcmHaFiqOaPOjoK+BIFzP4l0WxqZ10w53Se5IYcO2EUPsvmBA6TXeGes/EP/weJwi/wdo9wlHwK54921nUyF8WI+RQveuZTDCKWKqGiIIwSSjlhmDHjRIksIEQ1ksllU8Qt3tH3fVuzLYaULMMFRBJSACmBiuzEGUs2IDg7cjLGoDqr7DOqph0KKpQCI6Oz9nmJdvyz6AkMkuNKWahlT5sWEIOmpUfd5towCQJu8eR+WH1I4UFcUHFQO9bcnqSyYBhV1o2jbHROavdETrPTvE6zE1JIfiBm2rS2OC0krqxjoFNQujfiNW6Cu9wlteMd4PXklKqv1lGz7mPVBDADb9w5xyzAzwmsNtAp56qS7bn55+5Z7JTOMZRl0ls4FSg6FKdsrm/ZnY8IydnI1J8fUIxQB5rOInk7JIciPyd+QHGys5LmuAdyezruQyonPydpBjiDZ7QiHjVXPFQ6fso+C/DccvPIBxXRGaXxs4BU7Efhhe+lkIkXbh4i7ZvHD1vOAyR2pVkHVzrPonIUGkkBSiMcyeBjF5XjAf50pmVdWGcCzb+oHB99ny9ZUbnu4jqronJ8MId98KJyJ0su76JyfDC3fJyicieLL/MCS3x0RzxZUbnuojuvonJ8fK97ONFkWFSO5+5wD6g46KwU54l41ywz7/qRFJXjrpzmRrs9uxFo+cHkYSvyF+oCTO+/XPiaIFdN9d6tr6Zlr9Dr9erhYb2azh628lLiQmCznt7cKBAisNwKy9OT72od8I5+41+/lMNNPkzvZoe7/M/xLwbe0DkxV1UHvsm+SWE5P4u7xWYxXXqn6IS5dvdDZNdifuVoLj2/XV20tZaefiz5/O7qYUvr01JI9+vFal0ebkFgpZi0nMkPc/PSjpOa+xRKxvGUeWBdPWa9Y/fD8XmNplWNWb9VJHanBXJMjXwqs2PC1V0p572WfFrfTQ7BtIP4i079yL2XPtxvqaB9HkAou3SDn3pv9xOCG3vqhp3L+U35ydF2neu5+vX78GC5du6P1alR6eUFfVWO9Gmz2j1hp46h9koZqz8npdLsz0movQvEnP05ZTKb1BX67dahOqR1bPm66UmVGbS7Ll/bT7Jsd02gzl+pgt9Yh1nq7a6xI/KdrN2189zoc4/h8+4xTKBRu2DCgbAd62F7DOsfkJjCjpkqdcMkaxIrH+AF64CjsUlMotFJ7Hij9FBoTTcbNVc7E8+AyIhYOMg4TywI01QC0IEFV12vdFgICXyfVggh1MyorqsKj1yE1z9oFllwR4d8gqyXMvCalJlEkbbUYtT/Y5j0zNQoT9VLZoxGzMhj4oCSCDlLdRoUq8XChksoZfQBZ2QoatMgHygisxQlE6xnWFONRplhjjFm9rVMDcWQPY3ToFgB6ryhmFfdFgUeDE3wSL1D1QOKwtzSYdysjxoPih9/WU2/uXr7xw9/ss+zxa+E8c3DJPis0ml2S5/sNGxuFDMBeCGl1IUpXQVoSYFZVbmSOEwdDlnBxKEsTqpqlCHNJ06pRsleiteXby7sftHRalF68RKeqEGhEol5Gl7XIOO44OggUIdXDGgBHaf5ktWnDOk8kVcl2qDisy64TCCOWn42DmAgxgWoHaA1WAACUlBwgIxeuseuPhvS9iK2vu+z+XMRYCUhWpcQkLYTisWgKp3eCa2k0zS3iC2InKrv+eTdWnxPA761+J6+MBMjTlCDUJhwwrWrOSeNaiKKmrzjJq4eG5Q3dULB2COI71RnuVA2WBPRULZCWv1llX+N4qmcpA0kr/gNA82TjYyyJhj7YVwNWwACIAdMOc1AE6vOoaZq3eVKv6AkXP3/YfEeUAMxWrXkE8Bfq3osGnCFonux8N61l1vqJftU4dz4vsQsp0xQobxDwZlwYJYjxsqSbRLxniFObKTOQgL6sH/XysfUKI+iPFrXbWMVO3biAp240Ng6ZAPSF2zIBGcTyDE2dmAop0ZkMTw4xJC5n2OPFglF6qcDsyWuutkA2Ak51/JUsUOlMU4H7Ehkjma5V9Gw47iZztpKip1uXt0jxo6DKaiZ+9YBO9zMKaDI3G2Jhx37ZlQov4mkh0+37cAQ+MymDx8q89I+PPem/OeMUSaIzSn9GcoezcJs4q0PGICAkfY+mCS0kJJRiEt6NbacKOei3AfhTFJwqJBXBwKEBabV15EjGEoQLBCqxsAxAqPuaQ4IRIwXUGeIC4i58mmVyQyxFV2HQM0MBVxyziiRZqidcTtS6+wTRkIDtTbY/OAN7wnGGpDgvLmnjnmBMEaUYUy5ANhRZFFnpzaKQHCZCjcB58dit3MbXUgQmVKyhFTTWVc7t0SZfu7nC4i5jNdyUxHBbDE/5DYczcCLJLuJUHxBMBFMYMAFR814MCLbvU6P8JAcVHgBG9QJOopF3xJRK6ERRC47UnaJfzljyh1hUo+KeXUlE3uOybp9oUWvt+VbbIPgcLHvJhALF5kNZPyFNCNJ3VzPpQon7/T1wG59c8OL3XaQ8/MBOSy7JNeMaNhz3w9C310E894kkiPtfVDufM60IeHR+t95lpcuu4N9N1aiax4/T80jSrmUO0UELRtulBuCTVsIKCsXUYK5kFxSKXpm89Im7o1Sy1CouxwWGJGuyZ1bCYILBA4eX+AYNR2LSdmAyjJIISCOAiIl2XgAcZJRigOW5egexS6LynFc5EgVLD1GP6ewgkW33m3HRXFoJqELwsQXSyI+r7N28Dz3tZE6yqeVcjVWM6FcVhBCJCi3gDkUghjhHVqA+qunRV/GJRFFGHIoBWekyz0S0y1G+dJtlWZ+oFsB1WRhgBjGgiCbeymQtYAcl7qEXLPMJ3AMEl/7A3ZpH30El0aODVZwDY4vIQmLWlq0JM34Eubu+O54EVwdQx5yMQ+ODqYTEwU+MSFRyumgs9BWfSxcS32qOCDuVOAwqsk1jpzq+lLJgVaL2XiCSH8qcKiYbBLDTIu41WnGoTFZfWEmFhwWSDnNTCrzTflnUDZthtKZpaLsbIiRWvJM1g5OVGwMygrMDjrAZFieRzSTLWCL71gQNuOY0dnAn+QFf9p0WSBrWrdmvYBQxBNgjAv940aKyRJj4efOu6bNrgzYnx1epQqOGlqFMPHrlSPxPbrO5HXQnGADsjKSKhhRAb8DmZr9842PMtHcUWlMmnLeAfLnXxHlvNedMYfbhYVsbH9G6J7izpLN+jzzuaZf4fAgrjv9Sh91d2dfEVfbl2GddxIQ8s08/aq7kMz0q+5SQoO6jAQNL6ShErC6S2/CcMFqCVjGkRZlgjUTTuyWL0hnow8jvVNPv5ylt98rVUWDodWQ07TV6vzoC3Ox+ABxWQza94cG8fQz/zD13QSbN0nWT88tkPRVGvo4KyUlNLwVwZN5K8Egz2vnURLfomnjqh94GfcuzX5zOjV2A2LoY2QT9opiDUHPmSBXgckHKob8jNghD9Zzl9Lo9ClIpHgUBH2e9dgjCe9g3BzshOkRztlJe7I0YCdGt3Z1JBI1bWijEmPtkxm7YpSFuDfpz5vprJcqxsGYvTHJiKPzV8p0MJIogOnNO6oENmzekZ7bTKgRS+UKq8UUEiwglbBZvhf3rQSMSFmbTflmaghRVqgwUohIISmxar8NtYx37esR2hrn18kuQIbAX5/udO+az+o3lo08enTG+deP85ujraMufEXSM+weY1bMOZH+fHlYVPvyFc1J5Dg9yxxqBUmqMICzcuBzN5mz6ibDEDUXUCId0cFUjRjcwAqIDj614vteDcxk6VVwwkZptQnFOgG0T60FbtIeSVfx3D3DcXuCKMFP86ClvHuCMDPGp+x67YI3Dh4n6gnixkL6QF+oVDKnpbySEspVznADJpQiAyYdaMlM+FHgRMPG7Wj8IkDdMJCNaCkBop62bFeD6738EOXpdRo6WnUpChnz33mAJCx6aiHeJ4OxEwreETWab+h01e/a7jxIKTwakEj7NDDWRjYnFMZTNjPwYixZlby2Ow9WMq9bOPa5Zh6RsIWWTmA8/9BDV9Nz9rTKMnb6S3nlc/C0qy9JGfYCLoNIKgQBSYujtbPi1hbb1nJQPg9inCBgp6OR7d6n+hArQ/ZwOqeRRkxkIWg1Bje3qKPNrZbkk84jjn0I+ADY8OOlTJYp+/skR7PpSPMQMNafjpdGzAI0MvczwD2khJWnA2qVOVBDSkrXSzFZSlsPyaEh84h12muOyd4nlnHsILuGDvmEg13LWjrhZJcm3O9U5MiFGkFo2FUrQ2sKsb4wE3eD0cbCgJoGGgfOlaFzCjERnuWn5SaJXRB9gj+3LMxBazomgHleXjUmrD8Cg2EufVYWRL1w3vkEMej+pEnjP6zbdknGR/QTlXUMV77QYyqZKR9hPkiWVR9jaB9hvkWGjbrIKKO+XQlGizEg6t3v4rJb0TFHthJVvouo1S9KVXKQP7V4g6vBb/x4Q+d2zMhoUZ9dhIEnjjCc1Gg9oVx00pqOKRh1xcauZsUThxRO7IedTjATu2cHtkMIZNAQAu8WQhimAzYoENeVX/qfrUxu0jk6AHsXrFaTTmtGJibdIFXH1FrZMExg0zShzeo2A5885kPGDXroSR8HZ7It7NNUCYJEa8jBEWDrGYcI1ptQVyg3vUlVrow2VaVpftF+qnKGxcv4qbmZ0RUx2+oYKZQts7hDooJoFPqUDRLap1JgtHSrfCMNHFuZ4PtshsozvLCDC6R+khtihztSFk4TnuBONIsYBVjEz+GFi27eEu3uxQqHs5RTdAEF2Ia5Rxd6iEU2tVs5CW1yGbbwGUpctNwllmESFjoIK1hnqlJnw8jm1AMPT8dwo6F2m6ahVrtNX5iL3WbUGzfKnPXfIeLNcY3KZkNvCqFu5y8Gi691rV3WF/v9a56FawAO1YC8ivojA6kyjgJgU7HGxX/AwZCziaANweOZgJPoWmPa4cWwYPgAI9a3yQRvxneb1bQxDis03j1oZTwNcD7N0TUFN78uun0bhjxy0oiZcgsdavhcSeasKsmQHCvJQJioAeSjKyVT6WAmDL89ERuxlgwZv5YM1AUin4vJDMxM2Ir5jl5MBsL0qQ2Po5pMpTYZMZPuK3w4tdy/nAzh1ByNyWSJBPdv//P7/MV377//4bu/4eW71be3//w0ybuT4pG45Gyxnl/vR7tbrUvJp6xIxQBWhjEBWAJMBWx6sRNG+La1jv7YcfiKg8LVTgeqYflxDIaSjFOuWTVm7JnvdJovDE/iI5+y1OM5vusyYS3IyxxpAKot4+a+NKecF/Twad90KS4BLQjsd5fELBcQ63zqLEekwAokFcsZBjgjFObHclk1C3wsLMcDWY7nxXISlpW4D6+m4c+ZYqcILCcphgUB/e6SmOUCmhM+sxygfpYD+bGcM0b6THMn0pwMpDmZGc0hiLw0x6LQHFMmo4/mfHeJR3Nf4V+//vD5y9uPn6/mP/6yevHn5Qs+CYjr5kdzR6gqFM/evEYs6pRmMBqXtIXRCFCWnSvbRjkNEXLUnDJ0hUNHZ7QeKQTdU3VsRjOYpR/F+TSlTnHHrxuN0QhQbiMtGYcRKIyuPpAqp1IA/SnjRsHK8C4ulNaDOMw4NNR2n8ScFhARfua0A6fBHDktfY34Z06rNKWV03C+nIbwMJzWdp/EnHb2Wwuf5w+bpDTHqLLlj9McwzhDmstyZ+HR0Zxjq+H4dWPRnGTMQ3MY8gb99GQ5uj3IWd0Ed7lHYoY7+22FsRmOUpYhw2W5q/DoGM6xzXD8ukwZTpL0DOe/R2KGO/stheQMRyhvuKrIoDgO2rJDxqC4PLcUHh3HOfYYjl83FschCRreapN/EBExOG57lP4oybXcJPWGwlnuKNRZbj5NzHJ0V9j1KMsxSHJkOfTMckNsMwTvM4x7rBFwdJznMGYxeA4yzjzGnP8mqXnuLHcZsuI5inN0WOHz1sMgPBe69wBH3Xzw8xyBUXxWP8+13CQ1z7l2Hp4PW6XetGUQGOl0XMGkcDQJQ7pEfOzzVm44pN+xqCbcPhIVKqoj+XEM+wnwaBmLhDQ46p7DFmfGcWMOe2+hQkaJiVponuhKzVeufYRnvkrNVwQyC0c6lXE8skq/+fC0yGrU7YMSZNyiFwYK3aGgz2l2s0eG4itjtN58pf5cr0piOVxeFoH8aTWbl1f8Pw==</diagram></mxfile>" + height="3570px" + viewBox="-0.5 -0.5 3707 3570" + content="<mxfile host="Electron" modified="2023-11-15T07:03:18.394Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="8yBIGjeANrMFIPyocWYk" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">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</diagram></mxfile>" > - - + + - - - - + + + + - + - - + + - - - - - + + + + + - - - - - + + + + + - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + - + - + - + - + - + - + - - - - - + + + + + - - - - - + + + + + - + + + + - - - - + - +
@@ -306,7 +314,7 @@

- (Left-hand traffic) + Left-hand traffic, RightOfWay is set on the map

@@ -337,22 +345,22 @@
- Urban crossroads with traffic light... + Urban crossroads with traffic light... - - - - - - - - - - - - + + + + + + + + + + + - + - + - + - - - - - + + + + + - + - - - + + + - - + + - - - - + + + + - - - + + + - - + + - + - - - + + + - - - + + + - - + + - - - - - - - + + + + + + + - +
- ego lane + ego lane - - - + + +
- yield lane + yield lane - - - + + +
- attention lane + attention lane - - + +
@@ -639,60 +647,66 @@
- conflicting lanes + conflicting lanes - - - - - - - - + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - + + + + + + + - + - - - - + + + + - - - - - - + + + + + + - - - - - - + + + + + + - - - - - - - + + + + + + +
@@ -755,7 +769,7 @@

- (Right-hand traffic) + Right-hand traffic, RightOfWay is set on the map

@@ -786,16 +800,16 @@
- Urban crossroads with traffic light... + Urban crossroads with traffic light... - +
- ego lane + ego lane @@ -816,7 +830,7 @@
@@ -827,16 +841,16 @@
- conflicting lanes + conflicting lanes - +
- yield lane + yield lane - +
- attention lane + attention lane - - - - - - - + + + + + + + - - + + - - - - - - + + + + + + - - - - - + + + + + - - + + - - - + + + - + - + - - - - + + + + - - + +
@@ -1039,22 +1053,22 @@ T-shape junction w/o traffic light

- (Left-hand traffic) + Left-hand traffic, RightOfWay is not set on the map
- T-shape junction w/o traffic light... + T-shape junction w/o traffic light... - +
- ego lane + ego lane - - - + + +
- attention area + attention area - - - - - - + + + + + +
@@ -1111,30 +1125,31 @@ T-shape junction w/o traffic light

- (Right-hand traffic) + Right-hand traffic, RightOfWay is not set on the map +
- T-shape junction w/o traffic light... + T-shape junction w/o traffic light...
- - - - - + + + + + - - - + + + - - + + - - - - + + + + - +
- ego lane + ego lane - - - + + +
- attention area + attention area - - - - + + + + + + + + + + + + + + + + + + + - - + + - - + + - - + + - - + + - - + + + + +
+
+
+ attention area +
+
+
+
+ attention area +
+
+ + + + + + +
+
+
+ attention area +
+
+
+
+ attention area +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - + - - + + + + + + + + + + + + + + - - + + + + + + + + + + + + - - + + + + + +
+
+
+ + Urban crossroads with traffic light +
+
+ + Left-hand traffic, RightOfWay is not on the map +
+
+
+ + +
+
+
+
+
+
+
+ Urban crossroads with traffic light... +
+
+ + + + + + + + + + + + + + + - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + ego lane + +
+
+
+
+ ego lane +
+
+ + + + + + +
+
+
+ attention lane +
+
+
+
+ attention lane +
+
+ + + + + +
+
+
+ + conflicting lanes + +
+
+
+
+ conflicting lanes +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + Urban crossroads with traffic light +
+
+ + Right-hand traffic, RightOfWay is not set on the map +
+
+
+ + +
+
+
+
+
+
+
+ Urban crossroads with traffic light... +
+
+ + + + +
+
+
+ + ego lane + +
+
+
+
+ ego lane +
+
+ + + +
+
+
+ + conflicting lanes + +
+
+
+
+ conflicting lanes +
+
+ + + + +
+
+
+ attention lane +
+
+
+
+ attention lane +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
- attention area + attention area - - - + + +
- attention area + attention area - - + + diff --git a/planning/behavior_velocity_intersection_module/docs/intersection-stoplines.drawio.svg b/planning/behavior_velocity_intersection_module/docs/intersection-stoplines.drawio.svg new file mode 100644 index 0000000000000..67e4479f70d57 --- /dev/null +++ b/planning/behavior_velocity_intersection_module/docs/intersection-stoplines.drawio.svg @@ -0,0 +1,710 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + closest_idx + +
+
+
+
+ closest_idx +
+
+ + + + + + +
+
+
+ + stuck_stop_line + +
+
+
+
+ stuck_stop_line +
+
+ + + + + + + + + +
+
+
+ + default_stop_line + +
+
+
+
+ default_stop_line +
+
+ + + + + + +
+
+
+ + first_attention_stop_line + +
+
+
+
+ first_attention_stop_line +
+
+ + + + + + +
+
+
+ + + occlusion_peeking +
+ _stop_line +
+
+
+
+
+
+ occlusion_peeking... +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + + occlusion_wo_tl +
+ _pass_judge_line +
+
+
+
+
+
+
+ occlusion_wo_tl... +
+
+ + + + + + +
+
+
+ + closest_idx + +
+
+
+
+ closest_idx +
+
+ + + + + + + + + +
+
+
+ + stuck_stop_line + +
+
+
+
+ stuck_stop_line +
+
+ + + + + + +
+
+
+ + default_stop_line + +
+
+
+
+ default_stop_line +
+
+ + + + + + +
+
+
+ + first_attention_stop_line + +
+
+
+
+ first_attention_stop_line +
+
+ + + + + + +
+
+
+ + + occlusion_peeking +
+ _stop_line +
+
+
+
+
+
+ occlusion_peeking... +
+
+ + + + + + + + +
+
+
+ + + occlusion_wo_tl +
+ _pass_judge_line +
+
+
+
+
+
+
+ occlusion_wo_tl... +
+
+ + + + + + + + + +
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_intersection_module/docs/occlusion-with-tl.drawio.svg b/planning/behavior_velocity_intersection_module/docs/occlusion-with-tl.drawio.svg new file mode 100644 index 0000000000000..4edce74d53a7c --- /dev/null +++ b/planning/behavior_velocity_intersection_module/docs/occlusion-with-tl.drawio.svg @@ -0,0 +1,2002 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + ego + +
+
+
+
+ ego +
+
+ + + + + + + + + +
+
+
+ + nearest occlusion cell + +
+
+
+
+ nearest occlusion... +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + ego + +
+
+
+
+ ego +
+
+ + + + + + + +
+
+
+ + nearest occlusion cell + +
+
+
+
+ nearest occlusion... +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + + dynamically occluded by detected object +
+
+
+
+
+
+
+ dynamically occluded by detected object +
+
+ + + +
+
+
+ + + statically occluded because no detected object is blocking +
+
+
+
+
+
+
+ statically occluded because no detected object is blocking +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_intersection_module/docs/occlusion-without-tl.drawio.svg b/planning/behavior_velocity_intersection_module/docs/occlusion-without-tl.drawio.svg index 2fc22c8a4a401..697c0c634daf0 100644 --- a/planning/behavior_velocity_intersection_module/docs/occlusion-without-tl.drawio.svg +++ b/planning/behavior_velocity_intersection_module/docs/occlusion-without-tl.drawio.svg @@ -5,32 +5,32 @@ xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" version="1.1" - width="1653px" - height="522px" - viewBox="-0.5 -0.5 1653 522" - content="<mxfile host="Electron" modified="2023-10-03T05:36:02.775Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="BwI40dFIjy7ASgJYnXFl" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">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</diagram></mxfile>" + width="1357px" + height="600px" + viewBox="-0.5 -0.5 1357 600" + content="<mxfile host="Electron" modified="2023-11-14T20:57:10.757Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="Xql1fZtAubmV39K-nFIb" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">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</diagram></mxfile>" > - - - - + + + + - - - - - + + + + + - - + + - - - + + + - + - + - +
-
+
- - - default stop + + 1.stop at the default_ + + + + stopline + + + +
- line
-
- default stop... + 1.stop at the defa... - - - + + +
- occlusion + occlusion
- occlusion + occlusion
- - - - - - + + + + - + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - +
-
+
- - - - first attention -
- stop line -
-
-
-
+
+ + 2. stop at the first_attention_stopline + +
- first attentio... + 2. stop at the first_... - - - - - + + + + + - + + + + + + +
+
+
+
+ + 3. creep up to occlusion_wo_tl_ + + + pass_judge_line + +
+
+
+
+
+ 3. creep up to occlusion_wo_... +
+
+ + diff --git a/planning/behavior_velocity_intersection_module/docs/occlusion-wo-tl-creeping.png b/planning/behavior_velocity_intersection_module/docs/occlusion-wo-tl-creeping.png new file mode 100644 index 0000000000000..133b6947cbe42 Binary files /dev/null and b/planning/behavior_velocity_intersection_module/docs/occlusion-wo-tl-creeping.png differ diff --git a/planning/behavior_velocity_intersection_module/docs/occlusion_grid.drawio.svg b/planning/behavior_velocity_intersection_module/docs/occlusion_grid.drawio.svg index fc09a4212070a..ff1f9843c2b1d 100644 --- a/planning/behavior_velocity_intersection_module/docs/occlusion_grid.drawio.svg +++ b/planning/behavior_velocity_intersection_module/docs/occlusion_grid.drawio.svg @@ -5,30 +5,30 @@ xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" version="1.1" - width="2502px" + width="2523px" height="1392px" - viewBox="-0.5 -0.5 2502 1392" - content="<mxfile host="Electron" modified="2023-09-29T04:34:40.611Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="5DwL00YCo2z-J-veTRkD" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">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</diagram></mxfile>" + viewBox="-0.5 -0.5 2523 1392" + content="<mxfile host="Electron" modified="2023-11-13T12:12:55.311Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="LhhfO7V8Yd9xK0iSo8Ik" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">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</diagram></mxfile>" > - - - - - + + + + + - - - - - - - - - - - - - + + + + + + + + + + + + + - + - + - + - + - + - - - - - + + + + + - - - - - + + + + + - + - - - - + + + + - +
- default stop line + default_stopline
- default stop line + default_stopline
- - - + + + -
+
- occlusion peeking line + occlusion_peeking_stopline
- occlusion peeking line + occlusion_peeking_stopline - - - + + + - + - - - + + + - - + +
- ego + ego - - - + + +
- occlusion attent... + occlusion attent... - - + + - +
- stopped vehicle on attentio... + stopped vehicle on attentio... - - + + - + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
- + The cells behind blocking vehicles
are not marked as occluded -
+
- The cells behind blocking vehicles... + The cells behind blocking vehicles...
- - - + + + -
+
- mark the cells which is unknown and... + mark the cells which is unknown and... - - - + + + - - - + + + - - - - + + + + - - - - + + + +
@@ -1350,17 +1350,17 @@
- 13 + 13 - - + +
@@ -1369,17 +1369,17 @@
- 12 + 12 - - + +
@@ -1388,17 +1388,17 @@
- 12 + 12 - - + +
@@ -1407,32 +1407,32 @@
- 11 + 11 - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + +
@@ -1441,17 +1441,17 @@
- 12 + 12 - - + +
@@ -1460,17 +1460,17 @@
- 11 + 11 - - + +
@@ -1479,17 +1479,17 @@
- 11 + 11 - - + +
@@ -1498,32 +1498,32 @@
- 10 + 10 - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + +
@@ -1532,17 +1532,17 @@
- 11 + 11 - - + +
@@ -1551,17 +1551,17 @@
- 10 + 10 - - + +
@@ -1570,17 +1570,17 @@
- 10 + 10 - - + +
@@ -1589,32 +1589,32 @@
- 9 + 9 - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + +
@@ -1623,17 +1623,17 @@
- 10 + 10 - - + +
@@ -1642,17 +1642,17 @@
- 9 + 9 - - + +
@@ -1661,16 +1661,16 @@
- 9 + 9 - +
@@ -1679,32 +1679,32 @@
- 8 + 8 - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + +
@@ -1713,17 +1713,17 @@
- 9 + 9 - - + +
@@ -1732,16 +1732,16 @@
- 8 + 8 - +
@@ -1750,16 +1750,16 @@
- 8 + 8 - +
@@ -1768,33 +1768,33 @@
- 7 + 7 - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + +
@@ -1803,17 +1803,17 @@
- 8 + 8 - - + +
@@ -1822,16 +1822,16 @@
- 7 + 7 - +
@@ -1840,16 +1840,16 @@
- 7 + 7 - +
@@ -1858,33 +1858,33 @@
- 6 + 6 - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + +
@@ -1893,16 +1893,16 @@
- 7 + 7 - +
@@ -1911,16 +1911,16 @@
- 6 + 6 - +
@@ -1929,16 +1929,16 @@
- 6 + 6 - +
@@ -1947,33 +1947,33 @@
- 5 + 5 - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + +
@@ -1982,16 +1982,16 @@
- 6 + 6 - +
@@ -2000,16 +2000,16 @@
- 5 + 5 - +
@@ -2018,16 +2018,16 @@
- 5 + 5 - +
@@ -2036,33 +2036,33 @@
- 4 + 4 - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + +
@@ -2071,16 +2071,16 @@
- 5 + 5 - +
@@ -2089,16 +2089,16 @@
- 4 + 4 - +
@@ -2107,16 +2107,16 @@
- 4 + 4 - +
@@ -2125,33 +2125,33 @@
- 3 + 3 - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + +
@@ -2164,16 +2164,16 @@
- 4... + 4... - +
@@ -2182,16 +2182,16 @@
- 3 + 3 - +
@@ -2200,16 +2200,16 @@
- 3 + 3 - +
@@ -2218,32 +2218,32 @@
- 2 + 2 - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + +
@@ -2252,16 +2252,16 @@
- 3 + 3 - +
@@ -2270,16 +2270,16 @@
- 2 + 2 - +
@@ -2288,16 +2288,16 @@
- 2 + 2 - +
@@ -2306,32 +2306,32 @@
- 1 + 1 - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + +
@@ -2340,16 +2340,16 @@
- 2 + 2 - +
@@ -2358,16 +2358,16 @@
- 1 + 1 - +
@@ -2376,16 +2376,16 @@
- 1 + 1 - +
@@ -2394,32 +2394,32 @@
- 0 + 0 - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + +
@@ -2428,16 +2428,16 @@
- 1 + 1 - +
@@ -2446,34 +2446,34 @@
- 0 + 0 - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + +
@@ -2482,115 +2482,115 @@
- 0 + 0 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
- nearest occlusion... + nearest occlusion... diff --git a/planning/behavior_velocity_intersection_module/docs/signal-phase-group.drawio.svg b/planning/behavior_velocity_intersection_module/docs/signal-phase-group.drawio.svg new file mode 100644 index 0000000000000..6a268a9b83c6e --- /dev/null +++ b/planning/behavior_velocity_intersection_module/docs/signal-phase-group.drawio.svg @@ -0,0 +1,547 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + + Urban crossroads with traffic light +
+
+ (Left-hand traffic) +
+
+ inphase signal group + of lane + L1 +
+
+
+
+
+
+
+ Urban crossroads with traffic light... +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + + Urban crossroads with traffic light +
+
+ (Right-hand traffic) +
+
+
+ + antiphase signal group + of lane + L1 + + +
+
+
+
+
+
+
+ Urban crossroads with traffic light... +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ L1 +
+
+
+
+ L1 +
+
+ + + +
+
+
+ L1 +
+
+
+
+ L1 +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_intersection_module/docs/static-occlusion-timeout.png b/planning/behavior_velocity_intersection_module/docs/static-occlusion-timeout.png new file mode 100644 index 0000000000000..9bb9188db745f Binary files /dev/null and b/planning/behavior_velocity_intersection_module/docs/static-occlusion-timeout.png differ diff --git a/planning/behavior_velocity_intersection_module/docs/stuck-vehicle.drawio.svg b/planning/behavior_velocity_intersection_module/docs/stuck-vehicle.drawio.svg index c29cb7ade21cd..4cae662d8c764 100644 --- a/planning/behavior_velocity_intersection_module/docs/stuck-vehicle.drawio.svg +++ b/planning/behavior_velocity_intersection_module/docs/stuck-vehicle.drawio.svg @@ -539,13 +539,13 @@
- stop_line_margin + stopline_margin
- stop_line_margin + stopline_margin diff --git a/planning/behavior_velocity_intersection_module/docs/ugly-intersection.drawio.svg b/planning/behavior_velocity_intersection_module/docs/ugly-intersection.drawio.svg new file mode 100644 index 0000000000000..2e0581e8da378 --- /dev/null +++ b/planning/behavior_velocity_intersection_module/docs/ugly-intersection.drawio.svg @@ -0,0 +1,326 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + + complex/bad intersection map +
+
+
+
+
+
+
+ complex/bad intersection map +
+
+ + + +
+
+
+ + (1) ego lane is overlapped with adjacnet lane. +
+ This causes unnecessary attention lanes. +
+
+
+
+
+
+ (1) ego lane is overlapped with adjacnet lane.... +
+
+ + + + + +
+
+
+ + (2) ego lane is overlapped with unrelated lane +
+
+
+
+
+
+  (2) ego lane is overlapped with unrelated lane +
+
+ + + + + + + + + +
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_intersection_module/src/manager.cpp index 5de74aeb82d86..789708abe98f8 100644 --- a/planning/behavior_velocity_intersection_module/src/manager.cpp +++ b/planning/behavior_velocity_intersection_module/src/manager.cpp @@ -43,25 +43,20 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node) { const std::string ns(getModuleName()); auto & ip = intersection_param_; - ip.common.attention_area_margin = - getOrDeclareParameter(node, ns + ".common.attention_area_margin"); ip.common.attention_area_length = getOrDeclareParameter(node, ns + ".common.attention_area_length"); - ip.common.attention_area_angle_thr = + ip.common.attention_area_margin = + getOrDeclareParameter(node, ns + ".common.attention_area_margin"); + ip.common.attention_area_angle_threshold = getOrDeclareParameter(node, ns + ".common.attention_area_angle_threshold"); - ip.common.stop_line_margin = getOrDeclareParameter(node, ns + ".common.stop_line_margin"); - ip.common.intersection_velocity = - getOrDeclareParameter(node, ns + ".common.intersection_velocity"); - ip.common.intersection_max_acc = - getOrDeclareParameter(node, ns + ".common.intersection_max_accel"); - ip.common.stop_overshoot_margin = - getOrDeclareParameter(node, ns + ".common.stop_overshoot_margin"); ip.common.use_intersection_area = getOrDeclareParameter(node, ns + ".common.use_intersection_area"); + ip.common.default_stopline_margin = + getOrDeclareParameter(node, ns + ".common.default_stopline_margin"); + ip.common.stopline_overshoot_margin = + getOrDeclareParameter(node, ns + ".common.stopline_overshoot_margin"); ip.common.path_interpolation_ds = getOrDeclareParameter(node, ns + ".common.path_interpolation_ds"); - ip.common.consider_wrong_direction_vehicle = - getOrDeclareParameter(node, ns + ".common.consider_wrong_direction_vehicle"); ip.common.max_accel = getOrDeclareParameter(node, ns + ".common.max_accel"); ip.common.max_jerk = getOrDeclareParameter(node, ns + ".common.max_jerk"); ip.common.delay_response_time = @@ -77,33 +72,38 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node) getOrDeclareParameter(node, ns + ".stuck_vehicle.use_stuck_stopline"); ip.stuck_vehicle.stuck_vehicle_detect_dist = getOrDeclareParameter(node, ns + ".stuck_vehicle.stuck_vehicle_detect_dist"); - ip.stuck_vehicle.stuck_vehicle_vel_thr = - getOrDeclareParameter(node, ns + ".stuck_vehicle.stuck_vehicle_vel_thr"); - /* - ip.stuck_vehicle.assumed_front_car_decel = - getOrDeclareParameter(node, ns + ".stuck_vehicle.assumed_front_car_decel"); - ip.stuck_vehicle.enable_front_car_decel_prediction = - getOrDeclareParameter(node, ns + ".stuck_vehicle.enable_front_car_decel_prediction"); - */ + ip.stuck_vehicle.stuck_vehicle_velocity_threshold = + getOrDeclareParameter(node, ns + ".stuck_vehicle.stuck_vehicle_velocity_threshold"); ip.stuck_vehicle.timeout_private_area = getOrDeclareParameter(node, ns + ".stuck_vehicle.timeout_private_area"); ip.stuck_vehicle.enable_private_area_stuck_disregard = getOrDeclareParameter(node, ns + ".stuck_vehicle.enable_private_area_stuck_disregard"); - ip.stuck_vehicle.yield_stuck_turn_direction.left = - getOrDeclareParameter(node, ns + ".stuck_vehicle.yield_stuck.turn_direction.left"); - ip.stuck_vehicle.yield_stuck_turn_direction.right = - getOrDeclareParameter(node, ns + ".stuck_vehicle.yield_stuck.turn_direction.right"); - ip.stuck_vehicle.yield_stuck_turn_direction.straight = - getOrDeclareParameter(node, ns + ".stuck_vehicle.yield_stuck.turn_direction.straight"); - ip.stuck_vehicle.yield_stuck_distance_thr = - getOrDeclareParameter(node, ns + ".stuck_vehicle.yield_stuck.distance_thr"); + ip.yield_stuck.turn_direction.left = + getOrDeclareParameter(node, ns + ".yield_stuck.turn_direction.left"); + ip.yield_stuck.turn_direction.right = + getOrDeclareParameter(node, ns + ".yield_stuck.turn_direction.right"); + ip.yield_stuck.turn_direction.straight = + getOrDeclareParameter(node, ns + ".yield_stuck.turn_direction.straight"); + ip.yield_stuck.distance_threshold = + getOrDeclareParameter(node, ns + ".yield_stuck.distance_threshold"); + + ip.collision_detection.consider_wrong_direction_vehicle = + getOrDeclareParameter(node, ns + ".collision_detection.consider_wrong_direction_vehicle"); + ip.collision_detection.collision_detection_hold_time = + getOrDeclareParameter(node, ns + ".collision_detection.collision_detection_hold_time"); ip.collision_detection.min_predicted_path_confidence = getOrDeclareParameter(node, ns + ".collision_detection.min_predicted_path_confidence"); - ip.collision_detection.minimum_ego_predicted_velocity = - getOrDeclareParameter(node, ns + ".collision_detection.minimum_ego_predicted_velocity"); - ip.collision_detection.state_transit_margin_time = - getOrDeclareParameter(node, ns + ".collision_detection.state_transit_margin_time"); + ip.collision_detection.keep_detection_velocity_threshold = getOrDeclareParameter( + node, ns + ".collision_detection.keep_detection_velocity_threshold"); + ip.collision_detection.velocity_profile.use_upstream = + getOrDeclareParameter(node, ns + ".collision_detection.velocity_profile.use_upstream"); + ip.collision_detection.velocity_profile.minimum_upstream_velocity = getOrDeclareParameter( + node, ns + ".collision_detection.velocity_profile.minimum_upstream_velocity"); + ip.collision_detection.velocity_profile.default_velocity = getOrDeclareParameter( + node, ns + ".collision_detection.velocity_profile.default_velocity"); + ip.collision_detection.velocity_profile.minimum_default_velocity = getOrDeclareParameter( + node, ns + ".collision_detection.velocity_profile.minimum_default_velocity"); ip.collision_detection.fully_prioritized.collision_start_margin_time = getOrDeclareParameter( node, ns + ".collision_detection.fully_prioritized.collision_start_margin_time"); @@ -121,12 +121,6 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node) node, ns + ".collision_detection.not_prioritized.collision_start_margin_time"); ip.collision_detection.not_prioritized.collision_end_margin_time = getOrDeclareParameter( node, ns + ".collision_detection.not_prioritized.collision_end_margin_time"); - ip.collision_detection.keep_detection_vel_thr = - getOrDeclareParameter(node, ns + ".collision_detection.keep_detection_vel_thr"); - ip.collision_detection.use_upstream_velocity = - getOrDeclareParameter(node, ns + ".collision_detection.use_upstream_velocity"); - ip.collision_detection.minimum_upstream_velocity = - getOrDeclareParameter(node, ns + ".collision_detection.minimum_upstream_velocity"); ip.collision_detection.yield_on_green_traffic_light.distance_to_assigned_lanelet_start = getOrDeclareParameter( node, @@ -146,41 +140,35 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node) ip.occlusion.enable = getOrDeclareParameter(node, ns + ".occlusion.enable"); ip.occlusion.occlusion_attention_area_length = getOrDeclareParameter(node, ns + ".occlusion.occlusion_attention_area_length"); - ip.occlusion.enable_creeping = - getOrDeclareParameter(node, ns + ".occlusion.enable_creeping"); - ip.occlusion.occlusion_creep_velocity = - getOrDeclareParameter(node, ns + ".occlusion.occlusion_creep_velocity"); - ip.occlusion.peeking_offset = - getOrDeclareParameter(node, ns + ".occlusion.peeking_offset"); ip.occlusion.free_space_max = getOrDeclareParameter(node, ns + ".occlusion.free_space_max"); ip.occlusion.occupied_min = getOrDeclareParameter(node, ns + ".occlusion.occupied_min"); - ip.occlusion.do_dp = getOrDeclareParameter(node, ns + ".occlusion.do_dp"); - ip.occlusion.before_creep_stop_time = - getOrDeclareParameter(node, ns + ".occlusion.before_creep_stop_time"); - ip.occlusion.min_vehicle_brake_for_rss = - getOrDeclareParameter(node, ns + ".occlusion.min_vehicle_brake_for_rss"); - ip.occlusion.max_vehicle_velocity_for_rss = - getOrDeclareParameter(node, ns + ".occlusion.max_vehicle_velocity_for_rss"); ip.occlusion.denoise_kernel = getOrDeclareParameter(node, ns + ".occlusion.denoise_kernel"); + ip.occlusion.attention_lane_crop_curvature_threshold = + getOrDeclareParameter(node, ns + ".occlusion.attention_lane_crop_curvature_threshold"); + ip.occlusion.attention_lane_curvature_calculation_ds = + getOrDeclareParameter(node, ns + ".occlusion.attention_lane_curvature_calculation_ds"); + ip.occlusion.creep_during_peeking.enable = + getOrDeclareParameter(node, ns + ".occlusion.creep_during_peeking.enable"); + ip.occlusion.creep_during_peeking.creep_velocity = + getOrDeclareParameter(node, ns + ".occlusion.creep_during_peeking.creep_velocity"); + ip.occlusion.peeking_offset = + getOrDeclareParameter(node, ns + ".occlusion.peeking_offset"); ip.occlusion.possible_object_bbox = getOrDeclareParameter>(node, ns + ".occlusion.possible_object_bbox"); ip.occlusion.ignore_parked_vehicle_speed_threshold = getOrDeclareParameter(node, ns + ".occlusion.ignore_parked_vehicle_speed_threshold"); - ip.occlusion.stop_release_margin_time = - getOrDeclareParameter(node, ns + ".occlusion.stop_release_margin_time"); + ip.occlusion.occlusion_detection_hold_time = + getOrDeclareParameter(node, ns + ".occlusion.occlusion_detection_hold_time"); + ip.occlusion.temporal_stop_time_before_peeking = + getOrDeclareParameter(node, ns + ".occlusion.temporal_stop_time_before_peeking"); ip.occlusion.temporal_stop_before_attention_area = getOrDeclareParameter(node, ns + ".occlusion.temporal_stop_before_attention_area"); - ip.occlusion.absence_traffic_light.creep_velocity = - getOrDeclareParameter(node, ns + ".occlusion.absence_traffic_light.creep_velocity"); - ip.occlusion.absence_traffic_light.maximum_peeking_distance = getOrDeclareParameter( - node, ns + ".occlusion.absence_traffic_light.maximum_peeking_distance"); - ip.occlusion.attention_lane_crop_curvature_threshold = - getOrDeclareParameter(node, ns + ".occlusion.attention_lane_crop_curvature_threshold"); - ip.occlusion.attention_lane_curvature_calculation_ds = - getOrDeclareParameter(node, ns + ".occlusion.attention_lane_curvature_calculation_ds"); + ip.occlusion.creep_velocity_without_traffic_light = + getOrDeclareParameter(node, ns + ".occlusion.creep_velocity_without_traffic_light"); ip.occlusion.static_occlusion_with_traffic_light_timeout = getOrDeclareParameter( node, ns + ".occlusion.static_occlusion_with_traffic_light_timeout"); + ip.debug.ttc = getOrDeclareParameter>(node, ns + ".debug.ttc"); } @@ -220,8 +208,8 @@ void IntersectionModuleManager::launchNewModules( if (const auto tl_reg_elems = ll.regulatoryElementsAs(); tl_reg_elems.size() != 0) { const auto tl_reg_elem = tl_reg_elems.front(); - const auto stop_line_opt = tl_reg_elem->stopLine(); - if (!!stop_line_opt) has_traffic_light = true; + const auto stopline_opt = tl_reg_elem->stopLine(); + if (!!stopline_opt) has_traffic_light = true; } const auto new_module = std::make_shared( module_id, lane_id, planner_data_, intersection_param_, associative_ids, turn_direction, @@ -340,7 +328,7 @@ MergeFromPrivateModuleManager::MergeFromPrivateModuleManager(rclcpp::Node & node mp.stop_duration_sec = getOrDeclareParameter(node, ns + ".stop_duration_sec"); mp.attention_area_length = node.get_parameter("intersection.common.attention_area_length").as_double(); - mp.stop_line_margin = getOrDeclareParameter(node, ns + ".stop_line_margin"); + mp.stopline_margin = getOrDeclareParameter(node, ns + ".stopline_margin"); mp.path_interpolation_ds = node.get_parameter("intersection.common.path_interpolation_ds").as_double(); mp.stop_distance_threshold = getOrDeclareParameter(node, ns + ".stop_distance_threshold"); diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 4dd31609a4ff9..0d483b501d1ee 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -115,19 +115,21 @@ IntersectionModule::IntersectionModule( { collision_state_machine_.setMarginTime( - planner_param_.collision_detection.state_transit_margin_time); + planner_param_.collision_detection.collision_detection_hold_time); } { - before_creep_state_machine_.setMarginTime(planner_param_.occlusion.before_creep_stop_time); + before_creep_state_machine_.setMarginTime( + planner_param_.occlusion.temporal_stop_time_before_peeking); before_creep_state_machine_.setState(StateMachine::State::STOP); } { - occlusion_stop_state_machine_.setMarginTime(planner_param_.occlusion.stop_release_margin_time); + occlusion_stop_state_machine_.setMarginTime( + planner_param_.occlusion.occlusion_detection_hold_time); occlusion_stop_state_machine_.setState(StateMachine::State::GO); } { temporal_stop_before_attention_state_machine_.setMarginTime( - planner_param_.occlusion.before_creep_stop_time); + planner_param_.occlusion.occlusion_detection_hold_time); temporal_stop_before_attention_state_machine_.setState(StateMachine::State::STOP); } { @@ -193,14 +195,14 @@ void prepareRTCByDecisionResult( { RCLCPP_DEBUG(rclcpp::get_logger("prepareRTCByDecisionResult"), "StuckStop"); const auto closest_idx = result.closest_idx; - const auto stop_line_idx = result.stuck_stop_line_idx; + const auto stopline_idx = result.stuck_stopline_idx; *default_safety = false; - *default_distance = motion_utils::calcSignedArcLength(path.points, closest_idx, stop_line_idx); + *default_distance = motion_utils::calcSignedArcLength(path.points, closest_idx, stopline_idx); *occlusion_safety = true; - if (result.occlusion_stop_line_idx) { - const auto occlusion_stop_line_idx = result.occlusion_stop_line_idx.value(); + if (result.occlusion_stopline_idx) { + const auto occlusion_stopline_idx = result.occlusion_stopline_idx.value(); *occlusion_distance = - motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stop_line_idx); + motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stopline_idx); } return; } @@ -213,9 +215,9 @@ void prepareRTCByDecisionResult( { RCLCPP_DEBUG(rclcpp::get_logger("prepareRTCByDecisionResult"), "YieldStuckStop"); const auto closest_idx = result.closest_idx; - const auto stop_line_idx = result.stuck_stop_line_idx; + const auto stopline_idx = result.stuck_stopline_idx; *default_safety = false; - *default_distance = motion_utils::calcSignedArcLength(path.points, closest_idx, stop_line_idx); + *default_distance = motion_utils::calcSignedArcLength(path.points, closest_idx, stopline_idx); *occlusion_safety = true; return; } @@ -228,14 +230,14 @@ void prepareRTCByDecisionResult( { RCLCPP_DEBUG(rclcpp::get_logger("prepareRTCByDecisionResult"), "NonOccludedCollisionStop"); const auto closest_idx = result.closest_idx; - const auto collision_stop_line_idx = result.collision_stop_line_idx; + const auto collision_stopline_idx = result.collision_stopline_idx; *default_safety = false; *default_distance = - motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stop_line_idx); - const auto occlusion_stop_line = result.occlusion_stop_line_idx; + motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stopline_idx); + const auto occlusion_stopline = result.occlusion_stopline_idx; *occlusion_safety = true; *occlusion_distance = - motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stop_line); + motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stopline); return; } @@ -247,14 +249,14 @@ void prepareRTCByDecisionResult( { RCLCPP_DEBUG(rclcpp::get_logger("prepareRTCByDecisionResult"), "FirstWaitBeforeOcclusion"); const auto closest_idx = result.closest_idx; - const auto first_stop_line_idx = result.first_stop_line_idx; - const auto occlusion_stop_line_idx = result.occlusion_stop_line_idx; + const auto first_stopline_idx = result.first_stopline_idx; + const auto occlusion_stopline_idx = result.occlusion_stopline_idx; *default_safety = false; *default_distance = - motion_utils::calcSignedArcLength(path.points, closest_idx, first_stop_line_idx); + motion_utils::calcSignedArcLength(path.points, closest_idx, first_stopline_idx); *occlusion_safety = result.is_actually_occlusion_cleared; *occlusion_distance = - motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stop_line_idx); + motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stopline_idx); return; } @@ -266,14 +268,14 @@ void prepareRTCByDecisionResult( { RCLCPP_DEBUG(rclcpp::get_logger("prepareRTCByDecisionResult"), "PeekingTowardOcclusion"); const auto closest_idx = result.closest_idx; - const auto collision_stop_line_idx = result.collision_stop_line_idx; - const auto occlusion_stop_line_idx = result.occlusion_stop_line_idx; + const auto collision_stopline_idx = result.collision_stopline_idx; + const auto occlusion_stopline_idx = result.occlusion_stopline_idx; *default_safety = true; *default_distance = - motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stop_line_idx); + motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stopline_idx); *occlusion_safety = result.is_actually_occlusion_cleared; *occlusion_distance = - motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stop_line_idx); + motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stopline_idx); return; } @@ -285,10 +287,10 @@ void prepareRTCByDecisionResult( { RCLCPP_DEBUG(rclcpp::get_logger("prepareRTCByDecisionResult"), "OccludedAbsenceTrafficLight"); const auto closest_idx = result.closest_idx; - const auto collision_stop_line_idx = result.closest_idx; + const auto collision_stopline_idx = result.closest_idx; *default_safety = !result.collision_detected; *default_distance = - motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stop_line_idx); + motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stopline_idx); *occlusion_safety = result.is_actually_occlusion_cleared; *occlusion_distance = 0; return; @@ -302,14 +304,14 @@ void prepareRTCByDecisionResult( { RCLCPP_DEBUG(rclcpp::get_logger("prepareRTCByDecisionResult"), "OccludedCollisionStop"); const auto closest_idx = result.closest_idx; - const auto collision_stop_line_idx = result.collision_stop_line_idx; - const auto occlusion_stop_line_idx = result.occlusion_stop_line_idx; + const auto collision_stopline_idx = result.collision_stopline_idx; + const auto occlusion_stopline_idx = result.occlusion_stopline_idx; *default_safety = false; *default_distance = - motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stop_line_idx); + motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stopline_idx); *occlusion_safety = result.is_actually_occlusion_cleared; *occlusion_distance = - motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stop_line_idx); + motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stopline_idx); return; } @@ -321,33 +323,33 @@ void prepareRTCByDecisionResult( { RCLCPP_DEBUG(rclcpp::get_logger("prepareRTCByDecisionResult"), "Safe"); const auto closest_idx = result.closest_idx; - const auto collision_stop_line_idx = result.collision_stop_line_idx; - const auto occlusion_stop_line_idx = result.occlusion_stop_line_idx; + const auto collision_stopline_idx = result.collision_stopline_idx; + const auto occlusion_stopline_idx = result.occlusion_stopline_idx; *default_safety = true; *default_distance = - motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stop_line_idx); + motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stopline_idx); *occlusion_safety = true; *occlusion_distance = - motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stop_line_idx); + motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stopline_idx); return; } template <> void prepareRTCByDecisionResult( - const IntersectionModule::TrafficLightArrowSolidOn & result, + const IntersectionModule::FullyPrioritized & result, const autoware_auto_planning_msgs::msg::PathWithLaneId & path, bool * default_safety, double * default_distance, bool * occlusion_safety, double * occlusion_distance) { - RCLCPP_DEBUG(rclcpp::get_logger("prepareRTCByDecisionResult"), "TrafficLightArrowSolidOn"); + RCLCPP_DEBUG(rclcpp::get_logger("prepareRTCByDecisionResult"), "FullyPrioritized"); const auto closest_idx = result.closest_idx; - const auto collision_stop_line_idx = result.collision_stop_line_idx; - const auto occlusion_stop_line_idx = result.occlusion_stop_line_idx; + const auto collision_stopline_idx = result.collision_stopline_idx; + const auto occlusion_stopline_idx = result.occlusion_stopline_idx; *default_safety = !result.collision_detected; *default_distance = - motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stop_line_idx); + motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stopline_idx); *occlusion_safety = true; *occlusion_distance = - motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stop_line_idx); + motion_utils::calcSignedArcLength(path.points, closest_idx, occlusion_stopline_idx); return; } @@ -411,34 +413,34 @@ void reactRTCApprovalByDecisionResult( const auto closest_idx = decision_result.closest_idx; if (!rtc_default_approved) { // use default_rtc uuid for stuck vehicle detection - const auto stop_line_idx = decision_result.stuck_stop_line_idx; - planning_utils::setVelocityFromIndex(stop_line_idx, 0.0, path); + const auto stopline_idx = decision_result.stuck_stopline_idx; + planning_utils::setVelocityFromIndex(stopline_idx, 0.0, path); debug_data->collision_stop_wall_pose = - planning_utils::getAheadPose(stop_line_idx, baselink2front, *path); + planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stop_line_idx).point.pose; + stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; stop_factor.stop_factor_points = planning_utils::toRosPoints(debug_data->conflicting_targets); planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); } } if ( - !rtc_occlusion_approved && decision_result.occlusion_stop_line_idx && + !rtc_occlusion_approved && decision_result.occlusion_stopline_idx && planner_param.occlusion.enable) { - const auto occlusion_stop_line_idx = decision_result.occlusion_stop_line_idx.value(); - planning_utils::setVelocityFromIndex(occlusion_stop_line_idx, 0.0, path); + const auto occlusion_stopline_idx = decision_result.occlusion_stopline_idx.value(); + planning_utils::setVelocityFromIndex(occlusion_stopline_idx, 0.0, path); debug_data->occlusion_stop_wall_pose = - planning_utils::getAheadPose(occlusion_stop_line_idx, baselink2front, *path); + planning_utils::getAheadPose(occlusion_stopline_idx, baselink2front, *path); { tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(occlusion_stop_line_idx).point.pose; + stop_factor.stop_pose = path->points.at(occlusion_stopline_idx).point.pose; planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(closest_idx).point.pose, - path->points.at(occlusion_stop_line_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(occlusion_stopline_idx).point.pose, VelocityFactor::UNKNOWN); } } return; @@ -459,18 +461,18 @@ void reactRTCApprovalByDecisionResult( const auto closest_idx = decision_result.closest_idx; if (!rtc_default_approved) { // use default_rtc uuid for stuck vehicle detection - const auto stop_line_idx = decision_result.stuck_stop_line_idx; - planning_utils::setVelocityFromIndex(stop_line_idx, 0.0, path); + const auto stopline_idx = decision_result.stuck_stopline_idx; + planning_utils::setVelocityFromIndex(stopline_idx, 0.0, path); debug_data->collision_stop_wall_pose = - planning_utils::getAheadPose(stop_line_idx, baselink2front, *path); + planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stop_line_idx).point.pose; + stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; stop_factor.stop_factor_points = planning_utils::toRosPoints(debug_data->conflicting_targets); planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); } } return; @@ -489,31 +491,31 @@ void reactRTCApprovalByDecisionResult( "NonOccludedCollisionStop, approval = (default: %d, occlusion: %d)", rtc_default_approved, rtc_occlusion_approved); if (!rtc_default_approved) { - const auto stop_line_idx = decision_result.collision_stop_line_idx; - planning_utils::setVelocityFromIndex(stop_line_idx, 0.0, path); + const auto stopline_idx = decision_result.collision_stopline_idx; + planning_utils::setVelocityFromIndex(stopline_idx, 0.0, path); debug_data->collision_stop_wall_pose = - planning_utils::getAheadPose(stop_line_idx, baselink2front, *path); + planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stop_line_idx).point.pose; + stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); } } if (!rtc_occlusion_approved && planner_param.occlusion.enable) { - const auto stop_line_idx = decision_result.occlusion_stop_line_idx; - planning_utils::setVelocityFromIndex(stop_line_idx, 0.0, path); + const auto stopline_idx = decision_result.occlusion_stopline_idx; + planning_utils::setVelocityFromIndex(stopline_idx, 0.0, path); debug_data->occlusion_stop_wall_pose = - planning_utils::getAheadPose(stop_line_idx, baselink2front, *path); + planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stop_line_idx).point.pose; + stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); } } return; @@ -532,39 +534,39 @@ void reactRTCApprovalByDecisionResult( "FirstWaitBeforeOcclusion, approval = (default: %d, occlusion: %d)", rtc_default_approved, rtc_occlusion_approved); if (!rtc_default_approved) { - const auto stop_line_idx = decision_result.first_stop_line_idx; - planning_utils::setVelocityFromIndex(stop_line_idx, 0.0, path); + const auto stopline_idx = decision_result.first_stopline_idx; + planning_utils::setVelocityFromIndex(stopline_idx, 0.0, path); debug_data->occlusion_first_stop_wall_pose = - planning_utils::getAheadPose(stop_line_idx, baselink2front, *path); + planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stop_line_idx).point.pose; + stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); } } if (!rtc_occlusion_approved && planner_param.occlusion.enable) { - if (planner_param.occlusion.enable_creeping) { - const size_t occlusion_peeking_stop_line = decision_result.occlusion_stop_line_idx; + if (planner_param.occlusion.creep_during_peeking.enable) { + const size_t occlusion_peeking_stopline = decision_result.occlusion_stopline_idx; const size_t closest_idx = decision_result.closest_idx; - for (size_t i = closest_idx; i < occlusion_peeking_stop_line; i++) { + for (size_t i = closest_idx; i < occlusion_peeking_stopline; i++) { planning_utils::setVelocityFromIndex( - i, planner_param.occlusion.occlusion_creep_velocity, path); + i, planner_param.occlusion.creep_during_peeking.creep_velocity, path); } } - const auto stop_line_idx = decision_result.occlusion_stop_line_idx; - planning_utils::setVelocityFromIndex(stop_line_idx, 0.0, path); + const auto stopline_idx = decision_result.occlusion_stopline_idx; + planning_utils::setVelocityFromIndex(stopline_idx, 0.0, path); debug_data->occlusion_stop_wall_pose = - planning_utils::getAheadPose(stop_line_idx, baselink2front, *path); + planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stop_line_idx).point.pose; + stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); } } return; @@ -585,43 +587,43 @@ void reactRTCApprovalByDecisionResult( // NOTE: creep_velocity should be inserted first at closest_idx if !rtc_default_approved if (!rtc_occlusion_approved && planner_param.occlusion.enable) { - const size_t occlusion_peeking_stop_line = + const size_t occlusion_peeking_stopline = decision_result.temporal_stop_before_attention_required - ? decision_result.first_attention_stop_line_idx - : decision_result.occlusion_stop_line_idx; - if (planner_param.occlusion.enable_creeping) { + ? decision_result.first_attention_stopline_idx + : decision_result.occlusion_stopline_idx; + if (planner_param.occlusion.creep_during_peeking.enable) { const size_t closest_idx = decision_result.closest_idx; - for (size_t i = closest_idx; i < occlusion_peeking_stop_line; i++) { + for (size_t i = closest_idx; i < occlusion_peeking_stopline; i++) { planning_utils::setVelocityFromIndex( - i, planner_param.occlusion.occlusion_creep_velocity, path); + i, planner_param.occlusion.creep_during_peeking.creep_velocity, path); } } - planning_utils::setVelocityFromIndex(occlusion_peeking_stop_line, 0.0, path); + planning_utils::setVelocityFromIndex(occlusion_peeking_stopline, 0.0, path); debug_data->occlusion_stop_wall_pose = - planning_utils::getAheadPose(occlusion_peeking_stop_line, baselink2front, *path); + planning_utils::getAheadPose(occlusion_peeking_stopline, baselink2front, *path); debug_data->static_occlusion_with_traffic_light_timeout = decision_result.static_occlusion_timeout; { tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(occlusion_peeking_stop_line).point.pose; + stop_factor.stop_pose = path->points.at(occlusion_peeking_stopline).point.pose; planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(occlusion_peeking_stop_line).point.pose, VelocityFactor::UNKNOWN); + path->points.at(occlusion_peeking_stopline).point.pose, VelocityFactor::UNKNOWN); } } if (!rtc_default_approved) { - const auto stop_line_idx = decision_result.collision_stop_line_idx; - planning_utils::setVelocityFromIndex(stop_line_idx, 0.0, path); + const auto stopline_idx = decision_result.collision_stopline_idx; + planning_utils::setVelocityFromIndex(stopline_idx, 0.0, path); debug_data->collision_stop_wall_pose = - planning_utils::getAheadPose(stop_line_idx, baselink2front, *path); + planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stop_line_idx).point.pose; + stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); } } return; @@ -640,35 +642,35 @@ void reactRTCApprovalByDecisionResult( "OccludedCollisionStop, approval = (default: %d, occlusion: %d)", rtc_default_approved, rtc_occlusion_approved); if (!rtc_default_approved) { - const auto stop_line_idx = decision_result.collision_stop_line_idx; - planning_utils::setVelocityFromIndex(stop_line_idx, 0.0, path); + const auto stopline_idx = decision_result.collision_stopline_idx; + planning_utils::setVelocityFromIndex(stopline_idx, 0.0, path); debug_data->collision_stop_wall_pose = - planning_utils::getAheadPose(stop_line_idx, baselink2front, *path); + planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stop_line_idx).point.pose; + stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); } } if (!rtc_occlusion_approved && planner_param.occlusion.enable) { - const auto stop_line_idx = decision_result.temporal_stop_before_attention_required - ? decision_result.first_attention_stop_line_idx - : decision_result.occlusion_stop_line_idx; - planning_utils::setVelocityFromIndex(stop_line_idx, 0.0, path); + const auto stopline_idx = decision_result.temporal_stop_before_attention_required + ? decision_result.first_attention_stopline_idx + : decision_result.occlusion_stopline_idx; + planning_utils::setVelocityFromIndex(stopline_idx, 0.0, path); debug_data->occlusion_stop_wall_pose = - planning_utils::getAheadPose(stop_line_idx, baselink2front, *path); + planning_utils::getAheadPose(stopline_idx, baselink2front, *path); debug_data->static_occlusion_with_traffic_light_timeout = decision_result.static_occlusion_timeout; { tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stop_line_idx).point.pose; + stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); } } return; @@ -687,31 +689,31 @@ void reactRTCApprovalByDecisionResult( "OccludedAbsenceTrafficLight, approval = (default: %d, occlusion: %d)", rtc_default_approved, rtc_occlusion_approved); if (!rtc_default_approved) { - const auto stop_line_idx = decision_result.closest_idx; - planning_utils::setVelocityFromIndex(stop_line_idx, 0.0, path); + const auto stopline_idx = decision_result.closest_idx; + planning_utils::setVelocityFromIndex(stopline_idx, 0.0, path); debug_data->collision_stop_wall_pose = - planning_utils::getAheadPose(stop_line_idx, baselink2front, *path); + planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stop_line_idx).point.pose; + stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); } } if (!rtc_occlusion_approved && decision_result.temporal_stop_before_attention_required) { - const auto stop_line_idx = decision_result.first_attention_area_stop_line_idx; - planning_utils::setVelocityFromIndex(stop_line_idx, 0.0, path); + const auto stopline_idx = decision_result.first_attention_area_stopline_idx; + planning_utils::setVelocityFromIndex(stopline_idx, 0.0, path); debug_data->occlusion_stop_wall_pose = - planning_utils::getAheadPose(stop_line_idx, baselink2front, *path); + planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stop_line_idx).point.pose; + stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); } } if (!rtc_occlusion_approved && !decision_result.temporal_stop_before_attention_required) { @@ -719,7 +721,7 @@ void reactRTCApprovalByDecisionResult( const auto peeking_limit_line = decision_result.peeking_limit_line_idx; for (auto i = closest_idx; i <= peeking_limit_line; ++i) { planning_utils::setVelocityFromIndex( - i, planner_param.occlusion.absence_traffic_light.creep_velocity, path); + i, planner_param.occlusion.creep_velocity_without_traffic_light, path); } debug_data->absence_traffic_light_creep_wall = planning_utils::getAheadPose(closest_idx, baselink2front, *path); @@ -739,31 +741,31 @@ void reactRTCApprovalByDecisionResult( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), "Safe, approval = (default: %d, occlusion: %d)", rtc_default_approved, rtc_occlusion_approved); if (!rtc_default_approved) { - const auto stop_line_idx = decision_result.collision_stop_line_idx; - planning_utils::setVelocityFromIndex(stop_line_idx, 0.0, path); + const auto stopline_idx = decision_result.collision_stopline_idx; + planning_utils::setVelocityFromIndex(stopline_idx, 0.0, path); debug_data->collision_stop_wall_pose = - planning_utils::getAheadPose(stop_line_idx, baselink2front, *path); + planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stop_line_idx).point.pose; + stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); } } if (!rtc_occlusion_approved && planner_param.occlusion.enable) { - const auto stop_line_idx = decision_result.occlusion_stop_line_idx; - planning_utils::setVelocityFromIndex(stop_line_idx, 0.0, path); + const auto stopline_idx = decision_result.occlusion_stopline_idx; + planning_utils::setVelocityFromIndex(stopline_idx, 0.0, path); debug_data->occlusion_stop_wall_pose = - planning_utils::getAheadPose(stop_line_idx, baselink2front, *path); + planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stop_line_idx).point.pose; + stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); } } return; @@ -772,41 +774,41 @@ void reactRTCApprovalByDecisionResult( template <> void reactRTCApprovalByDecisionResult( const bool rtc_default_approved, const bool rtc_occlusion_approved, - const IntersectionModule::TrafficLightArrowSolidOn & decision_result, + const IntersectionModule::FullyPrioritized & decision_result, [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, const double baselink2front, autoware_auto_planning_msgs::msg::PathWithLaneId * path, StopReason * stop_reason, VelocityFactorInterface * velocity_factor, util::DebugData * debug_data) { RCLCPP_DEBUG( rclcpp::get_logger("reactRTCApprovalByDecisionResult"), - "TrafficLightArrowSolidOn, approval = (default: %d, occlusion: %d)", rtc_default_approved, + "FullyPrioritized, approval = (default: %d, occlusion: %d)", rtc_default_approved, rtc_occlusion_approved); if (!rtc_default_approved) { - const auto stop_line_idx = decision_result.collision_stop_line_idx; - planning_utils::setVelocityFromIndex(stop_line_idx, 0.0, path); + const auto stopline_idx = decision_result.collision_stopline_idx; + planning_utils::setVelocityFromIndex(stopline_idx, 0.0, path); debug_data->collision_stop_wall_pose = - planning_utils::getAheadPose(stop_line_idx, baselink2front, *path); + planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stop_line_idx).point.pose; + stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); } } if (!rtc_occlusion_approved && planner_param.occlusion.enable) { - const auto stop_line_idx = decision_result.occlusion_stop_line_idx; - planning_utils::setVelocityFromIndex(stop_line_idx, 0.0, path); + const auto stopline_idx = decision_result.occlusion_stopline_idx; + planning_utils::setVelocityFromIndex(stopline_idx, 0.0, path); debug_data->occlusion_stop_wall_pose = - planning_utils::getAheadPose(stop_line_idx, baselink2front, *path); + planning_utils::getAheadPose(stopline_idx, baselink2front, *path); { tier4_planning_msgs::msg::StopFactor stop_factor; - stop_factor.stop_pose = path->points.at(stop_line_idx).point.pose; + stop_factor.stop_pose = path->points.at(stopline_idx).point.pose; planning_utils::appendStopReason(stop_factor, stop_reason); velocity_factor->set( path->points, path->points.at(decision_result.closest_idx).point.pose, - path->points.at(stop_line_idx).point.pose, VelocityFactor::UNKNOWN); + path->points.at(stopline_idx).point.pose, VelocityFactor::UNKNOWN); } } return; @@ -859,8 +861,8 @@ static std::string formatDecisionResult(const IntersectionModule::DecisionResult if (std::holds_alternative(decision_result)) { return "OccludedAbsenceTrafficLight"; } - if (std::holds_alternative(decision_result)) { - return "TrafficLightArrowSolidOn"; + if (std::holds_alternative(decision_result)) { + return "FullyPrioritized"; } return ""; } @@ -959,7 +961,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( lanelet_map_ptr, routing_graph_ptr, assigned_lanelet, lanelets_on_path, associative_ids_, planner_param_.common.attention_area_length, planner_param_.occlusion.occlusion_attention_area_length, - planner_param_.common.consider_wrong_direction_vehicle); + planner_param_.collision_detection.consider_wrong_direction_vehicle); } auto & intersection_lanelets = intersection_lanelets_.value(); @@ -993,20 +995,20 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( intersection_lanelets.first_attention_lane() ? intersection_lanelets.first_attention_lane().value().centerline2d() : first_conflicting_lane.centerline2d(); - const auto intersection_stop_lines_opt = util::generateIntersectionStopLines( + const auto intersection_stoplines_opt = util::generateIntersectionStopLines( first_conflicting_area, dummy_first_attention_area, dummy_first_attention_lane_centerline, planner_data_, interpolated_path_info, planner_param_.stuck_vehicle.use_stuck_stopline, - planner_param_.common.stop_line_margin, planner_param_.common.max_accel, + planner_param_.common.default_stopline_margin, planner_param_.common.max_accel, planner_param_.common.max_jerk, planner_param_.common.delay_response_time, planner_param_.occlusion.peeking_offset, path); - if (!intersection_stop_lines_opt) { - return IntersectionModule::Indecisive{"failed to generate intersection_stop_lines"}; + if (!intersection_stoplines_opt) { + return IntersectionModule::Indecisive{"failed to generate intersection_stoplines"}; } - const auto & intersection_stop_lines = intersection_stop_lines_opt.value(); + const auto & intersection_stoplines = intersection_stoplines_opt.value(); const auto - [closest_idx, stuck_stop_line_idx_opt, default_stop_line_idx_opt, - first_attention_stop_line_idx_opt, occlusion_peeking_stop_line_idx_opt, - default_pass_judge_line_idx, occlusion_wo_tl_pass_judge_line_idx] = intersection_stop_lines; + [closest_idx, stuck_stopline_idx_opt, default_stopline_idx_opt, + first_attention_stopline_idx_opt, occlusion_peeking_stopline_idx_opt, + default_pass_judge_line_idx, occlusion_wo_tl_pass_judge_line_idx] = intersection_stoplines; // see the doc for struct PathLanelets const auto & conflicting_area = intersection_lanelets.conflicting_area(); @@ -1027,7 +1029,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( [&](const size_t pos, const double duration, StateMachine & state_machine) { const double dist_stopline = fromEgoDist(pos); const bool approached_dist_stopline = - (std::fabs(dist_stopline) < planner_param_.common.stop_overshoot_margin); + (std::fabs(dist_stopline) < planner_param_.common.stopline_overshoot_margin); const bool over_stopline = (dist_stopline < 0.0); const bool is_stopped_duration = planner_data_->isVehicleStopped(duration); if (over_stopline) { @@ -1040,8 +1042,8 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( auto stoppedAtPosition = [&](const size_t pos, const double duration) { const double dist_stopline = fromEgoDist(pos); const bool approached_dist_stopline = - (std::fabs(dist_stopline) < planner_param_.common.stop_overshoot_margin); - const bool over_stopline = (dist_stopline < -planner_param_.common.stop_overshoot_margin); + (std::fabs(dist_stopline) < planner_param_.common.stopline_overshoot_margin); + const bool over_stopline = (dist_stopline < -planner_param_.common.stopline_overshoot_margin); const bool is_stopped = planner_data_->isVehicleStopped(duration); if (over_stopline) { return true; @@ -1054,17 +1056,17 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( // stuck vehicle detection is viable even if attention area is empty // so this needs to be checked before attention area validation const bool stuck_detected = checkStuckVehicle(planner_data_, path_lanelets); - if (stuck_detected && stuck_stop_line_idx_opt) { - auto stuck_stop_line_idx = stuck_stop_line_idx_opt.value(); + if (stuck_detected && stuck_stopline_idx_opt) { + auto stuck_stopline_idx = stuck_stopline_idx_opt.value(); if (is_private_area_ && planner_param_.stuck_vehicle.enable_private_area_stuck_disregard) { if ( - default_stop_line_idx_opt && - fromEgoDist(stuck_stop_line_idx) < -planner_param_.common.stop_overshoot_margin) { - stuck_stop_line_idx = default_stop_line_idx_opt.value(); + default_stopline_idx_opt && + fromEgoDist(stuck_stopline_idx) < -planner_param_.common.stopline_overshoot_margin) { + stuck_stopline_idx = default_stopline_idx_opt.value(); } } else { return IntersectionModule::StuckStop{ - closest_idx, stuck_stop_line_idx, occlusion_peeking_stop_line_idx_opt}; + closest_idx, stuck_stopline_idx, occlusion_peeking_stopline_idx_opt}; } } @@ -1072,9 +1074,9 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( // so this needs to be checked before attention area validation const bool yield_stuck_detected = checkYieldStuckVehicle( planner_data_, path_lanelets, intersection_lanelets.first_attention_area()); - if (yield_stuck_detected && stuck_stop_line_idx_opt) { - const auto stuck_stop_line_idx = stuck_stop_line_idx_opt.value(); - return IntersectionModule::YieldStuckStop{closest_idx, stuck_stop_line_idx}; + if (yield_stuck_detected && stuck_stopline_idx_opt) { + const auto stuck_stopline_idx = stuck_stopline_idx_opt.value(); + return IntersectionModule::YieldStuckStop{closest_idx, stuck_stopline_idx}; } // if attention area is empty, collision/occlusion detection is impossible @@ -1085,21 +1087,20 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( // if attention area is not null but default stop line is not available, ego/backward-path has // already passed the stop line - if (!default_stop_line_idx_opt) { + if (!default_stopline_idx_opt) { return IntersectionModule::Indecisive{"default stop line is null"}; } // occlusion stop line is generated from the intersection of ego footprint along the path with the // attention area, so if this is null, eog has already passed the intersection - if (!first_attention_stop_line_idx_opt || !occlusion_peeking_stop_line_idx_opt) { + if (!first_attention_stopline_idx_opt || !occlusion_peeking_stopline_idx_opt) { return IntersectionModule::Indecisive{"occlusion stop line is null"}; } - const auto default_stop_line_idx = default_stop_line_idx_opt.value(); - const bool is_over_default_stop_line = - util::isOverTargetIndex(*path, closest_idx, current_pose, default_stop_line_idx); - const auto collision_stop_line_idx = - is_over_default_stop_line ? closest_idx : default_stop_line_idx; - const auto first_attention_stop_line_idx = first_attention_stop_line_idx_opt.value(); - const auto occlusion_stop_line_idx = occlusion_peeking_stop_line_idx_opt.value(); + const auto default_stopline_idx = default_stopline_idx_opt.value(); + const bool is_over_default_stopline = + util::isOverTargetIndex(*path, closest_idx, current_pose, default_stopline_idx); + const auto collision_stopline_idx = is_over_default_stopline ? closest_idx : default_stopline_idx; + const auto first_attention_stopline_idx = first_attention_stopline_idx_opt.value(); + const auto occlusion_stopline_idx = occlusion_peeking_stopline_idx_opt.value(); const auto & adjacent_lanelets = intersection_lanelets.adjacent(); const auto & occlusion_attention_lanelets = intersection_lanelets.occlusion_attention(); @@ -1123,9 +1124,6 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( // filter objects auto target_objects = generateTargetObjects(intersection_lanelets, intersection_area); - const double occlusion_dist_thr = std::fabs( - std::pow(planner_param_.occlusion.max_vehicle_velocity_for_rss, 2) / - (2 * planner_param_.occlusion.min_vehicle_brake_for_rss)); const double is_amber_or_red = (traffic_prioritized_level == util::TrafficPrioritizedLevel::PARTIALLY_PRIORITIZED) || (traffic_prioritized_level == util::TrafficPrioritizedLevel::FULLY_PRIORITIZED); @@ -1134,7 +1132,8 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( ? getOcclusionStatus( *planner_data_->occupancy_grid, occlusion_attention_area, adjacent_lanelets, first_attention_area, interpolated_path_info, occlusion_attention_divisions, - target_objects, current_pose, occlusion_dist_thr) + target_objects, current_pose, + planner_param_.occlusion.occlusion_required_clearance_distance) : OcclusionType::NOT_OCCLUDED; occlusion_stop_state_machine_.setStateWithMarginTime( occlusion_status == OcclusionType::NOT_OCCLUDED ? StateMachine::State::GO : StateMachine::STOP, @@ -1159,7 +1158,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( // if occlusion detection is enabled, pass_judge position is beyond the boundary of first // attention area if (has_traffic_light_) { - return occlusion_stop_line_idx; + return occlusion_stopline_idx; } else if (is_occlusion_state) { // if there is no traffic light and occlusion is detected, pass_judge position is beyond // the boundary of first attention area @@ -1180,15 +1179,14 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( planner_data_->current_velocity->twist.linear.x, planner_data_->current_velocity->twist.linear.y); const bool keep_detection = - (vel_norm < planner_param_.collision_detection.keep_detection_vel_thr); + (vel_norm < planner_param_.collision_detection.keep_detection_velocity_threshold); const bool was_safe = std::holds_alternative(prev_decision_result_); // if ego is over the pass judge line and not stopped - if (is_over_default_stop_line && !is_over_pass_judge_line && keep_detection) { - RCLCPP_DEBUG( - logger_, "is_over_default_stop_line && !is_over_pass_judge_line && keep_detection"); + if (is_over_default_stopline && !is_over_pass_judge_line && keep_detection) { + RCLCPP_DEBUG(logger_, "is_over_default_stopline && !is_over_pass_judge_line && keep_detection"); // do nothing } else if ( - (was_safe && is_over_default_stop_line && is_over_pass_judge_line && is_go_out_) || + (was_safe && is_over_default_stopline && is_over_pass_judge_line && is_go_out_) || is_permanent_go_) { // is_go_out_: previous RTC approval // activated_: current RTC approval @@ -1221,8 +1219,8 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const bool exist_close_vehicles = std::any_of( target_objects.all_attention_objects.begin(), target_objects.all_attention_objects.end(), [&](const auto & object) { - return object.dist_to_stop_line.has_value() && - object.dist_to_stop_line.value() < + return object.dist_to_stopline.has_value() && + object.dist_to_stopline.value() < planner_param_.collision_detection.yield_on_green_traffic_light .object_dist_to_stopline; }); @@ -1231,20 +1229,21 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( rclcpp::Duration((now - initial_green_light_observed_time_.value())).seconds() < planner_param_.collision_detection.yield_on_green_traffic_light.duration) { return IntersectionModule::NonOccludedCollisionStop{ - closest_idx, collision_stop_line_idx, occlusion_stop_line_idx}; + closest_idx, collision_stopline_idx, occlusion_stopline_idx}; } } } // calculate dynamic collision around attention area - const double time_to_restart = (is_go_out_ || is_prioritized) - ? 0.0 - : (planner_param_.collision_detection.state_transit_margin_time - - collision_state_machine_.getDuration()); + const double time_to_restart = + (is_go_out_ || is_prioritized) + ? 0.0 + : (planner_param_.collision_detection.collision_detection_hold_time - + collision_state_machine_.getDuration()); const bool has_collision = checkCollision( *path, &target_objects, path_lanelets, closest_idx, - std::min(occlusion_stop_line_idx, path->points.size() - 1), time_to_restart, + std::min(occlusion_stopline_idx, path->points.size() - 1), time_to_restart, traffic_prioritized_level); collision_state_machine_.setStateWithMarginTime( has_collision ? StateMachine::State::STOP : StateMachine::State::GO, @@ -1253,23 +1252,23 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( collision_state_machine_.getState() == StateMachine::State::STOP; if (is_prioritized) { - return TrafficLightArrowSolidOn{ - has_collision_with_margin, closest_idx, collision_stop_line_idx, occlusion_stop_line_idx}; + return FullyPrioritized{ + has_collision_with_margin, closest_idx, collision_stopline_idx, occlusion_stopline_idx}; } // Safe if (!is_occlusion_state && !has_collision_with_margin) { - return IntersectionModule::Safe{closest_idx, collision_stop_line_idx, occlusion_stop_line_idx}; + return IntersectionModule::Safe{closest_idx, collision_stopline_idx, occlusion_stopline_idx}; } // Only collision if (!is_occlusion_state && has_collision_with_margin) { return IntersectionModule::NonOccludedCollisionStop{ - closest_idx, collision_stop_line_idx, occlusion_stop_line_idx}; + closest_idx, collision_stopline_idx, occlusion_stopline_idx}; } // Occluded // occlusion_status is assured to be not NOT_OCCLUDED const bool stopped_at_default_line = stoppedForDuration( - default_stop_line_idx, planner_param_.occlusion.before_creep_stop_time, + default_stopline_idx, planner_param_.occlusion.temporal_stop_time_before_peeking, before_creep_state_machine_); if (stopped_at_default_line) { // if specified the parameter occlusion.temporal_stop_before_attention_area OR @@ -1277,7 +1276,8 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const bool temporal_stop_before_attention_required = (planner_param_.occlusion.temporal_stop_before_attention_area || !has_traffic_light_) ? !stoppedForDuration( - first_attention_stop_line_idx, planner_param_.occlusion.before_creep_stop_time, + first_attention_stopline_idx, + planner_param_.occlusion.temporal_stop_time_before_peeking, temporal_stop_before_attention_state_machine_) : false; if (!has_traffic_light_) { @@ -1286,15 +1286,19 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( "already passed maximum peeking line in the absence of traffic light"}; } return IntersectionModule::OccludedAbsenceTrafficLight{ - is_occlusion_cleared_with_margin, has_collision_with_margin, - temporal_stop_before_attention_required, closest_idx, - first_attention_stop_line_idx, occlusion_wo_tl_pass_judge_line_idx}; + is_occlusion_cleared_with_margin, + has_collision_with_margin, + temporal_stop_before_attention_required, + closest_idx, + first_attention_stopline_idx, + occlusion_wo_tl_pass_judge_line_idx}; } // following remaining block is "has_traffic_light_" // if ego is stuck by static occlusion in the presence of traffic light, start timeout count const bool is_static_occlusion = occlusion_status == OcclusionType::STATICALLY_OCCLUDED; const bool is_stuck_by_static_occlusion = - stoppedAtPosition(occlusion_stop_line_idx, planner_param_.occlusion.before_creep_stop_time) && + stoppedAtPosition( + occlusion_stopline_idx, planner_param_.occlusion.temporal_stop_time_before_peeking) && is_static_occlusion; if (has_collision_with_margin) { // if collision is detected, timeout is reset @@ -1306,13 +1310,12 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const bool release_static_occlusion_stuck = (static_occlusion_timeout_state_machine_.getState() == StateMachine::State::GO); if (!has_collision_with_margin && release_static_occlusion_stuck) { - return IntersectionModule::Safe{ - closest_idx, collision_stop_line_idx, occlusion_stop_line_idx}; + return IntersectionModule::Safe{closest_idx, collision_stopline_idx, occlusion_stopline_idx}; } // occlusion_status is either STATICALLY_OCCLUDED or DYNAMICALLY_OCCLUDED const double max_timeout = planner_param_.occlusion.static_occlusion_with_traffic_light_timeout + - planner_param_.occlusion.stop_release_margin_time; + planner_param_.occlusion.occlusion_detection_hold_time; const std::optional static_occlusion_timeout = is_stuck_by_static_occlusion ? std::make_optional( @@ -1320,29 +1323,31 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( occlusion_stop_state_machine_.getDuration()) : (is_static_occlusion ? std::make_optional(max_timeout) : std::nullopt); if (has_collision_with_margin) { - return IntersectionModule::OccludedCollisionStop{is_occlusion_cleared_with_margin, - temporal_stop_before_attention_required, - closest_idx, - collision_stop_line_idx, - first_attention_stop_line_idx, - occlusion_stop_line_idx, - static_occlusion_timeout}; + return IntersectionModule::OccludedCollisionStop{ + is_occlusion_cleared_with_margin, + temporal_stop_before_attention_required, + closest_idx, + collision_stopline_idx, + first_attention_stopline_idx, + occlusion_stopline_idx, + static_occlusion_timeout}; } else { - return IntersectionModule::PeekingTowardOcclusion{is_occlusion_cleared_with_margin, - temporal_stop_before_attention_required, - closest_idx, - collision_stop_line_idx, - first_attention_stop_line_idx, - occlusion_stop_line_idx, - static_occlusion_timeout}; + return IntersectionModule::PeekingTowardOcclusion{ + is_occlusion_cleared_with_margin, + temporal_stop_before_attention_required, + closest_idx, + collision_stopline_idx, + first_attention_stopline_idx, + occlusion_stopline_idx, + static_occlusion_timeout}; } } else { - const auto occlusion_stop_line = + const auto occlusion_stopline = (planner_param_.occlusion.temporal_stop_before_attention_area || !has_traffic_light_) - ? first_attention_stop_line_idx - : occlusion_stop_line_idx; + ? first_attention_stopline_idx + : occlusion_stopline_idx; return IntersectionModule::FirstWaitBeforeOcclusion{ - is_occlusion_cleared_with_margin, closest_idx, default_stop_line_idx, occlusion_stop_line}; + is_occlusion_cleared_with_margin, closest_idx, default_stopline_idx, occlusion_stopline}; } } @@ -1366,8 +1371,8 @@ bool IntersectionModule::checkStuckVehicle( debug_data_.stuck_vehicle_detect_area = toGeomPoly(stuck_vehicle_detect_area); return util::checkStuckVehicleInIntersection( - objects_ptr, stuck_vehicle_detect_area, planner_param_.stuck_vehicle.stuck_vehicle_vel_thr, - &debug_data_); + objects_ptr, stuck_vehicle_detect_area, + planner_param_.stuck_vehicle.stuck_vehicle_velocity_threshold, &debug_data_); } bool IntersectionModule::checkYieldStuckVehicle( @@ -1379,12 +1384,9 @@ bool IntersectionModule::checkYieldStuckVehicle( } const bool yield_stuck_detection_direction = [&]() { - return (turn_direction_ == "left" && - planner_param_.stuck_vehicle.yield_stuck_turn_direction.left) || - (turn_direction_ == "right" && - planner_param_.stuck_vehicle.yield_stuck_turn_direction.right) || - (turn_direction_ == "straight" && - planner_param_.stuck_vehicle.yield_stuck_turn_direction.straight); + return (turn_direction_ == "left" && planner_param_.yield_stuck.turn_direction.left) || + (turn_direction_ == "right" && planner_param_.yield_stuck.turn_direction.right) || + (turn_direction_ == "straight" && planner_param_.yield_stuck.turn_direction.straight); }(); if (!yield_stuck_detection_direction) { return false; @@ -1397,8 +1399,8 @@ bool IntersectionModule::checkYieldStuckVehicle( return util::checkYieldStuckVehicleInIntersection( objects_ptr, ego_poly, first_attention_area.value(), - planner_param_.stuck_vehicle.stuck_vehicle_vel_thr, - planner_param_.stuck_vehicle.yield_stuck_distance_thr, &debug_data_); + planner_param_.stuck_vehicle.stuck_vehicle_velocity_threshold, + planner_param_.yield_stuck.distance_threshold, &debug_data_); } util::TargetObjects IntersectionModule::generateTargetObjects( @@ -1410,7 +1412,7 @@ util::TargetObjects IntersectionModule::generateTargetObjects( util::TargetObjects target_objects; target_objects.header = objects_ptr->header; const auto & attention_lanelets = intersection_lanelets.attention(); - const auto & attention_lanelet_stoplines = intersection_lanelets.attention_stop_lines(); + const auto & attention_lanelet_stoplines = intersection_lanelets.attention_stoplines(); const auto & adjacent_lanelets = intersection_lanelets.adjacent(); for (const auto & object : objects_ptr->objects) { // ignore non-vehicle type objects, such as pedestrian. @@ -1421,8 +1423,8 @@ util::TargetObjects IntersectionModule::generateTargetObjects( // check direction of objects const auto object_direction = util::getObjectPoseWithVelocityDirection(object.kinematics); const auto belong_adjacent_lanelet_id = util::checkAngleForTargetLanelets( - object_direction, adjacent_lanelets, planner_param_.common.attention_area_angle_thr, - planner_param_.common.consider_wrong_direction_vehicle, + object_direction, adjacent_lanelets, planner_param_.common.attention_area_angle_threshold, + planner_param_.collision_detection.consider_wrong_direction_vehicle, planner_param_.common.attention_area_margin, false); if (belong_adjacent_lanelet_id) { continue; @@ -1438,27 +1440,27 @@ util::TargetObjects IntersectionModule::generateTargetObjects( const auto obj_poly = tier4_autoware_utils::toPolygon2d(object); const auto intersection_area_2d = intersection_area.value(); const auto belong_attention_lanelet_id = util::checkAngleForTargetLanelets( - object_direction, attention_lanelets, planner_param_.common.attention_area_angle_thr, - planner_param_.common.consider_wrong_direction_vehicle, + object_direction, attention_lanelets, planner_param_.common.attention_area_angle_threshold, + planner_param_.collision_detection.consider_wrong_direction_vehicle, planner_param_.common.attention_area_margin, is_parked_vehicle); if (belong_attention_lanelet_id) { const auto id = belong_attention_lanelet_id.value(); util::TargetObject target_object; target_object.object = object; target_object.attention_lanelet = attention_lanelets.at(id); - target_object.stop_line = attention_lanelet_stoplines.at(id); + target_object.stopline = attention_lanelet_stoplines.at(id); container.push_back(target_object); } else if (bg::within(Point2d{obj_pos.x, obj_pos.y}, intersection_area_2d)) { util::TargetObject target_object; target_object.object = object; target_object.attention_lanelet = std::nullopt; - target_object.stop_line = std::nullopt; + target_object.stopline = std::nullopt; target_objects.intersection_area_objects.push_back(target_object); } } else if (const auto belong_attention_lanelet_id = util::checkAngleForTargetLanelets( object_direction, attention_lanelets, - planner_param_.common.attention_area_angle_thr, - planner_param_.common.consider_wrong_direction_vehicle, + planner_param_.common.attention_area_angle_threshold, + planner_param_.collision_detection.consider_wrong_direction_vehicle, planner_param_.common.attention_area_margin, is_parked_vehicle); belong_attention_lanelet_id.has_value()) { // intersection_area is not available, use detection_area_with_margin as before @@ -1466,7 +1468,7 @@ util::TargetObjects IntersectionModule::generateTargetObjects( util::TargetObject target_object; target_object.object = object; target_object.attention_lanelet = attention_lanelets.at(id); - target_object.stop_line = attention_lanelet_stoplines.at(id); + target_object.stopline = attention_lanelet_stoplines.at(id); container.push_back(target_object); } } @@ -1477,7 +1479,7 @@ util::TargetObjects IntersectionModule::generateTargetObjects( target_objects.all_attention_objects.push_back(object); } for (auto & object : target_objects.all_attention_objects) { - object.calc_dist_to_stop_line(); + object.calc_dist_to_stopline(); } return target_objects; } @@ -1485,7 +1487,7 @@ util::TargetObjects IntersectionModule::generateTargetObjects( bool IntersectionModule::checkCollision( const autoware_auto_planning_msgs::msg::PathWithLaneId & path, util::TargetObjects * target_objects, const util::PathLanelets & path_lanelets, - const size_t closest_idx, const size_t last_intersection_stop_line_candidate_idx, + const size_t closest_idx, const size_t last_intersection_stopline_candidate_idx, const double time_delay, const util::TrafficPrioritizedLevel & traffic_prioritized_level) { using lanelet::utils::getArcCoordinates; @@ -1496,11 +1498,12 @@ bool IntersectionModule::checkCollision( tier4_debug_msgs::msg::Float64MultiArrayStamped ego_ttc_time_array; const auto time_distance_array = util::calcIntersectionPassingTime( path, planner_data_, lane_id_, associative_ids_, closest_idx, - last_intersection_stop_line_candidate_idx, time_delay, - planner_param_.common.intersection_velocity, - planner_param_.collision_detection.minimum_ego_predicted_velocity, - planner_param_.collision_detection.use_upstream_velocity, - planner_param_.collision_detection.minimum_upstream_velocity, &ego_ttc_time_array); + last_intersection_stopline_candidate_idx, time_delay, + planner_param_.collision_detection.velocity_profile.default_velocity, + planner_param_.collision_detection.velocity_profile.minimum_default_velocity, + planner_param_.collision_detection.velocity_profile.use_upstream, + planner_param_.collision_detection.velocity_profile.minimum_upstream_velocity, + &ego_ttc_time_array); if ( std::find(planner_param_.debug.ttc.begin(), planner_param_.debug.ttc.end(), lane_id_) != @@ -1536,11 +1539,11 @@ bool IntersectionModule::checkCollision( planner_param_.collision_detection.not_prioritized.collision_end_margin_time); }(); const auto expectedToStopBeforeStopLine = [&](const util::TargetObject & target_object) { - if (!target_object.dist_to_stop_line) { + if (!target_object.dist_to_stopline) { return false; } - const double dist_to_stop_line = target_object.dist_to_stop_line.value(); - if (dist_to_stop_line < 0) { + const double dist_to_stopline = target_object.dist_to_stopline.value(); + if (dist_to_stopline < 0) { return false; } const double v = target_object.object.kinematics.initial_twist_with_covariance.twist.linear.x; @@ -1548,25 +1551,25 @@ bool IntersectionModule::checkCollision( v * v / (2.0 * std::fabs(planner_param_.collision_detection.ignore_on_amber_traffic_light .object_expected_deceleration)); - return dist_to_stop_line > braking_distance; + return dist_to_stopline > braking_distance; }; const auto isTolerableOvershoot = [&](const util::TargetObject & target_object) { if ( - !target_object.attention_lanelet || !target_object.dist_to_stop_line || - !target_object.stop_line) { + !target_object.attention_lanelet || !target_object.dist_to_stopline || + !target_object.stopline) { return false; } - const double dist_to_stop_line = target_object.dist_to_stop_line.value(); + const double dist_to_stopline = target_object.dist_to_stopline.value(); const double v = target_object.object.kinematics.initial_twist_with_covariance.twist.linear.x; const double braking_distance = v * v / (2.0 * std::fabs(planner_param_.collision_detection.ignore_on_amber_traffic_light .object_expected_deceleration)); - if (dist_to_stop_line > braking_distance) { + if (dist_to_stopline > braking_distance) { return false; } - const auto stopline_front = target_object.stop_line.value().front(); - const auto stopline_back = target_object.stop_line.value().back(); + const auto stopline_front = target_object.stopline.value().front(); + const auto stopline_back = target_object.stopline.value().back(); tier4_autoware_utils::LineString2d object_line; object_line.emplace_back( (stopline_front.x() + stopline_back.x()) / 2.0, @@ -1581,7 +1584,7 @@ bool IntersectionModule::checkCollision( } const auto collision_point = intersections.front(); // distance from object expected stop position to collision point - const double stopline_to_object = -1.0 * dist_to_stop_line + braking_distance; + const double stopline_to_object = -1.0 * dist_to_stopline + braking_distance; const double stopline_to_collision = std::hypot(collision_point.x() - stopline_mid.x(), collision_point.y() - stopline_mid.y()); const double object2collision = stopline_to_collision - stopline_to_object; diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index 2c862abc0cdb6..4c33c0960afc3 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -49,66 +49,69 @@ class IntersectionModule : public SceneModuleInterface { struct Common { - double attention_area_margin; //! used for detecting objects in attention area - double attention_area_length; //! used to create attention area polygon - double attention_area_angle_thr; //! threshold in checking the angle of detecting objects - double stop_line_margin; //! distance from auto-generated stopline to detection_area boundary - double intersection_velocity; //! used for intersection passing time - double intersection_max_acc; //! used for calculating intersection velocity - double stop_overshoot_margin; //! overshoot margin for stuck, collision detection + double attention_area_length; + double attention_area_margin; + double attention_area_angle_threshold; bool use_intersection_area; - bool consider_wrong_direction_vehicle; + double default_stopline_margin; + double stopline_overshoot_margin; double path_interpolation_ds; double max_accel; double max_jerk; double delay_response_time; } common; + + struct TurnDirection + { + bool left; + bool right; + bool straight; + }; + struct StuckVehicle { - struct TurnDirection - { - bool left; - bool right; - bool straight; - }; TurnDirection turn_direction; - bool use_stuck_stopline; //! stopline generate before the intersection lanelet when is_stuck. - double stuck_vehicle_detect_dist; //! distance from end point to finish stuck vehicle check - double stuck_vehicle_vel_thr; //! Threshold of the speed to be recognized as stopped - /* - double - assumed_front_car_decel; //! the expected deceleration of front car when front car as well - bool enable_front_car_decel_prediction; //! flag for using above feature - */ + bool use_stuck_stopline; + double stuck_vehicle_detect_dist; + double stuck_vehicle_velocity_threshold; double timeout_private_area; bool enable_private_area_stuck_disregard; - double yield_stuck_distance_thr; - TurnDirection yield_stuck_turn_direction; } stuck_vehicle; + + struct YieldStuck + { + TurnDirection turn_direction; + double distance_threshold; + } yield_stuck; + struct CollisionDetection { + bool consider_wrong_direction_vehicle; + double collision_detection_hold_time; double min_predicted_path_confidence; - //! minimum confidence value of predicted path to use for collision detection - double minimum_ego_predicted_velocity; //! used to calculate ego's future velocity profile - double state_transit_margin_time; + double keep_detection_velocity_threshold; + struct VelocityProfile + { + bool use_upstream; + double minimum_upstream_velocity; + double default_velocity; + double minimum_default_velocity; + } velocity_profile; struct FullyPrioritized { - double collision_start_margin_time; //! start margin time to check collision - double collision_end_margin_time; //! end margin time to check collision + double collision_start_margin_time; + double collision_end_margin_time; } fully_prioritized; struct PartiallyPrioritized { - double collision_start_margin_time; //! start margin time to check collision - double collision_end_margin_time; //! end margin time to check collision + double collision_start_margin_time; + double collision_end_margin_time; } partially_prioritized; struct NotPrioritized { - double collision_start_margin_time; //! start margin time to check collision - double collision_end_margin_time; //! end margin time to check collision + double collision_start_margin_time; + double collision_end_margin_time; } not_prioritized; - double keep_detection_vel_thr; //! keep detection if ego is ego.vel < keep_detection_vel_thr - bool use_upstream_velocity; - double minimum_upstream_velocity; struct YieldOnGreeTrafficLight { double distance_to_assigned_lanelet_start; @@ -124,33 +127,32 @@ class IntersectionModule : public SceneModuleInterface double object_margin_to_path; } ignore_on_red_traffic_light; } collision_detection; + struct Occlusion { bool enable; - double occlusion_attention_area_length; //! used for occlusion detection - bool enable_creeping; - double occlusion_creep_velocity; //! the creep velocity to occlusion limit stop line - double peeking_offset; + double occlusion_attention_area_length; int free_space_max; int occupied_min; - bool do_dp; - double before_creep_stop_time; - double min_vehicle_brake_for_rss; - double max_vehicle_velocity_for_rss; double denoise_kernel; + double attention_lane_crop_curvature_threshold; + double attention_lane_curvature_calculation_ds; + struct CreepDuringPeeking + { + bool enable; + double creep_velocity; + } creep_during_peeking; + double peeking_offset; + double occlusion_required_clearance_distance; std::vector possible_object_bbox; double ignore_parked_vehicle_speed_threshold; - double stop_release_margin_time; + double occlusion_detection_hold_time; + double temporal_stop_time_before_peeking; bool temporal_stop_before_attention_area; - struct AbsenceTrafficLight - { - double creep_velocity; - double maximum_peeking_distance; - } absence_traffic_light; - double attention_lane_crop_curvature_threshold; - double attention_lane_curvature_calculation_ds; + double creep_velocity_without_traffic_light; double static_occlusion_with_traffic_light_timeout; } occlusion; + struct Debug { std::vector ttc; @@ -171,26 +173,26 @@ class IntersectionModule : public SceneModuleInterface struct StuckStop { size_t closest_idx{0}; - size_t stuck_stop_line_idx{0}; - std::optional occlusion_stop_line_idx{std::nullopt}; + size_t stuck_stopline_idx{0}; + std::optional occlusion_stopline_idx{std::nullopt}; }; struct YieldStuckStop { size_t closest_idx{0}; - size_t stuck_stop_line_idx{0}; + size_t stuck_stopline_idx{0}; }; struct NonOccludedCollisionStop { size_t closest_idx{0}; - size_t collision_stop_line_idx{0}; - size_t occlusion_stop_line_idx{0}; + size_t collision_stopline_idx{0}; + size_t occlusion_stopline_idx{0}; }; struct FirstWaitBeforeOcclusion { bool is_actually_occlusion_cleared{false}; size_t closest_idx{0}; - size_t first_stop_line_idx{0}; - size_t occlusion_stop_line_idx{0}; + size_t first_stopline_idx{0}; + size_t occlusion_stopline_idx{0}; }; // A state peeking to occlusion limit line in the presence of traffic light struct PeekingTowardOcclusion @@ -200,9 +202,9 @@ class IntersectionModule : public SceneModuleInterface bool is_actually_occlusion_cleared{false}; bool temporal_stop_before_attention_required{false}; size_t closest_idx{0}; - size_t collision_stop_line_idx{0}; - size_t first_attention_stop_line_idx{0}; - size_t occlusion_stop_line_idx{0}; + size_t collision_stopline_idx{0}; + size_t first_attention_stopline_idx{0}; + size_t occlusion_stopline_idx{0}; // if null, it is dynamic occlusion and shows up intersection_occlusion(dyn) // if valid, it contains the remaining time to release the static occlusion stuck and shows up // intersection_occlusion(x.y) @@ -214,9 +216,9 @@ class IntersectionModule : public SceneModuleInterface bool is_actually_occlusion_cleared{false}; bool temporal_stop_before_attention_required{false}; size_t closest_idx{0}; - size_t collision_stop_line_idx{0}; - size_t first_attention_stop_line_idx{0}; - size_t occlusion_stop_line_idx{0}; + size_t collision_stopline_idx{0}; + size_t first_attention_stopline_idx{0}; + size_t occlusion_stopline_idx{0}; // if null, it is dynamic occlusion and shows up intersection_occlusion(dyn) // if valid, it contains the remaining time to release the static occlusion stuck std::optional static_occlusion_timeout{std::nullopt}; @@ -227,22 +229,22 @@ class IntersectionModule : public SceneModuleInterface bool collision_detected{false}; bool temporal_stop_before_attention_required{false}; size_t closest_idx{0}; - size_t first_attention_area_stop_line_idx{0}; + size_t first_attention_area_stopline_idx{0}; size_t peeking_limit_line_idx{0}; }; struct Safe { // NOTE: if RTC is disapproved status, default stop lines are still needed. size_t closest_idx{0}; - size_t collision_stop_line_idx{0}; - size_t occlusion_stop_line_idx{0}; + size_t collision_stopline_idx{0}; + size_t occlusion_stopline_idx{0}; }; - struct TrafficLightArrowSolidOn + struct FullyPrioritized { bool collision_detected{false}; size_t closest_idx{0}; - size_t collision_stop_line_idx{0}; - size_t occlusion_stop_line_idx{0}; + size_t collision_stopline_idx{0}; + size_t occlusion_stopline_idx{0}; }; using DecisionResult = std::variant< Indecisive, // internal process error, or over the pass judge line @@ -254,7 +256,7 @@ class IntersectionModule : public SceneModuleInterface OccludedCollisionStop, // occlusion and collision are both detected OccludedAbsenceTrafficLight, // occlusion is detected in the absence of traffic light Safe, // judge as safe - TrafficLightArrowSolidOn // only detect vehicles violating traffic rules + FullyPrioritized // only detect vehicles violating traffic rules >; IntersectionModule( @@ -345,7 +347,7 @@ class IntersectionModule : public SceneModuleInterface bool checkCollision( const autoware_auto_planning_msgs::msg::PathWithLaneId & path, util::TargetObjects * target_objects, const util::PathLanelets & path_lanelets, - const size_t closest_idx, const size_t last_intersection_stop_line_candidate_idx, + const size_t closest_idx, const size_t last_intersection_stopline_candidate_idx, const double time_delay, const util::TrafficPrioritizedLevel & traffic_prioritized_level); OcclusionType getOcclusionStatus( diff --git a/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp b/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp index 63bca9d6c0577..b373f2cbc1c8a 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.cpp @@ -105,39 +105,39 @@ bool MergeFromPrivateRoadModule::modifyPathVelocity(PathWithLaneId * path, StopR } /* set stop-line and stop-judgement-line for base_link */ - const auto stop_line_idx_opt = util::generateStuckStopLine( + const auto stopline_idx_opt = util::generateStuckStopLine( first_conflicting_area.value(), planner_data_, interpolated_path_info, - planner_param_.stop_line_margin, false, path); - if (!stop_line_idx_opt.has_value()) { + planner_param_.stopline_margin, false, path); + if (!stopline_idx_opt.has_value()) { RCLCPP_WARN_SKIPFIRST_THROTTLE(logger_, *clock_, 1000 /* ms */, "setStopLineIdx fail"); return false; } - const size_t stop_line_idx = stop_line_idx_opt.value(); - if (stop_line_idx == 0) { + const size_t stopline_idx = stopline_idx_opt.value(); + if (stopline_idx == 0) { RCLCPP_DEBUG(logger_, "stop line is at path[0], ignore planning."); return true; } debug_data_.virtual_wall_pose = planning_utils::getAheadPose( - stop_line_idx, planner_data_->vehicle_info_.max_longitudinal_offset_m, *path); - debug_data_.stop_point_pose = path->points.at(stop_line_idx).point.pose; + stopline_idx, planner_data_->vehicle_info_.max_longitudinal_offset_m, *path); + debug_data_.stop_point_pose = path->points.at(stopline_idx).point.pose; /* set stop speed */ if (state_machine_.getState() == StateMachine::State::STOP) { constexpr double v = 0.0; - planning_utils::setVelocityFromIndex(stop_line_idx, v, path); + planning_utils::setVelocityFromIndex(stopline_idx, v, path); /* get stop point and stop factor */ tier4_planning_msgs::msg::StopFactor stop_factor; stop_factor.stop_pose = debug_data_.stop_point_pose; planning_utils::appendStopReason(stop_factor, stop_reason); - const auto & stop_pose = path->points.at(stop_line_idx).point.pose; + const auto & stop_pose = path->points.at(stopline_idx).point.pose; velocity_factor_.set( path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::UNKNOWN); const double signed_arc_dist_to_stop_point = motion_utils::calcSignedArcLength( - path->points, current_pose.position, path->points.at(stop_line_idx).point.pose.position); + path->points, current_pose.position, path->points.at(stopline_idx).point.pose.position); if ( signed_arc_dist_to_stop_point < planner_param_.stop_distance_threshold && diff --git a/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp b/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp index 3d0fa818c42f8..fab0303640700 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_merge_from_private_road.hpp @@ -56,7 +56,7 @@ class MergeFromPrivateRoadModule : public SceneModuleInterface struct PlannerParam { double attention_area_length; - double stop_line_margin; + double stopline_margin; double stop_duration_sec; double stop_distance_threshold; double path_interpolation_ds; diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index 19fa5a790b491..1c7e366347fec 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -171,22 +171,22 @@ static std::optional getStopLineIndexFromMap( planner_data->route_handler_->getLaneletMapPtr()->laneletLayer.get( interpolated_path_info.lane_id); const auto road_markings = lanelet.regulatoryElementsAs(); - lanelet::ConstLineStrings3d stop_line; + lanelet::ConstLineStrings3d stopline; for (const auto & road_marking : road_markings) { const std::string type = road_marking->roadMarking().attributeOr(lanelet::AttributeName::Type, "none"); if (type == lanelet::AttributeValueString::StopLine) { - stop_line.push_back(road_marking->roadMarking()); - break; // only one stop_line exists. + stopline.push_back(road_marking->roadMarking()); + break; // only one stopline exists. } } - if (stop_line.empty()) { + if (stopline.empty()) { return std::nullopt; } - const auto p_start = stop_line.front().front(); - const auto p_end = stop_line.front().back(); - const LineString2d extended_stop_line = + const auto p_start = stopline.front().front(); + const auto p_end = stopline.front().back(); + const LineString2d extended_stopline = planning_utils::extendLine(p_start, p_end, planner_data->stop_line_extend_length); for (size_t i = lane_interval.first; i < lane_interval.second; i++) { @@ -195,7 +195,7 @@ static std::optional getStopLineIndexFromMap( const LineString2d path_segment = {{p_front.x, p_front.y}, {p_back.x, p_back.y}}; std::vector collision_points; - bg::intersection(extended_stop_line, path_segment, collision_points); + bg::intersection(extended_stopline, path_segment, collision_points); if (collision_points.empty()) { continue; @@ -269,7 +269,7 @@ std::optional generateIntersectionStopLines( const lanelet::ConstLineString2d & first_attention_lane_centerline, const std::shared_ptr & planner_data, const InterpolatedPathInfo & interpolated_path_info, const bool use_stuck_stopline, - const double stop_line_margin, const double max_accel, const double max_jerk, + const double stopline_margin, const double max_accel, const double max_jerk, const double delay_response_time, const double peeking_offset, autoware_auto_planning_msgs::msg::PathWithLaneId * original_path) { @@ -278,7 +278,7 @@ std::optional generateIntersectionStopLines( const auto & lane_interval_ip = interpolated_path_info.lane_id_interval.value(); const double baselink2front = planner_data->vehicle_info_.max_longitudinal_offset_m; - const int stop_line_margin_idx_dist = std::ceil(stop_line_margin / ds); + const int stopline_margin_idx_dist = std::ceil(stopline_margin / ds); const int base2front_idx_dist = std::ceil(planner_data->vehicle_info_.max_longitudinal_offset_m / ds); @@ -310,19 +310,19 @@ std::optional generateIntersectionStopLines( first_footprint_attention_centerline_ip_opt.value(); // (1) default stop line position on interpolated path - bool default_stop_line_valid = true; + bool default_stopline_valid = true; int stop_idx_ip_int = -1; if (const auto map_stop_idx_ip = getStopLineIndexFromMap(interpolated_path_info, planner_data); map_stop_idx_ip) { stop_idx_ip_int = static_cast(map_stop_idx_ip.value()) - base2front_idx_dist; } if (stop_idx_ip_int < 0) { - stop_idx_ip_int = first_footprint_inside_detection_ip - stop_line_margin_idx_dist; + stop_idx_ip_int = first_footprint_inside_detection_ip - stopline_margin_idx_dist; } if (stop_idx_ip_int < 0) { - default_stop_line_valid = false; + default_stopline_valid = false; } - const auto default_stop_line_ip = stop_idx_ip_int >= 0 ? static_cast(stop_idx_ip_int) : 0; + const auto default_stopline_ip = stop_idx_ip_int >= 0 ? static_cast(stop_idx_ip_int) : 0; // (2) ego front stop line position on interpolated path const geometry_msgs::msg::Pose & current_pose = planner_data->current_odometry->pose; @@ -331,11 +331,11 @@ std::optional generateIntersectionStopLines( planner_data->ego_nearest_yaw_threshold); // (3) occlusion peeking stop line position on interpolated path - int occlusion_peeking_line_ip_int = static_cast(default_stop_line_ip); + int occlusion_peeking_line_ip_int = static_cast(default_stopline_ip); bool occlusion_peeking_line_valid = true; // NOTE: if footprints[0] is already inside the detection area, invalid { - const auto & base_pose0 = path_ip.points.at(default_stop_line_ip).point.pose; + const auto & base_pose0 = path_ip.points.at(default_stopline_ip).point.pose; const auto path_footprint0 = tier4_autoware_utils::transformVector( local_footprint, tier4_autoware_utils::pose2transform(base_pose0)); if (bg::intersects( @@ -350,8 +350,8 @@ std::optional generateIntersectionStopLines( const auto occlusion_peeking_line_ip = static_cast( std::clamp(occlusion_peeking_line_ip_int, 0, static_cast(path_ip.points.size()) - 1)); - const auto first_attention_stop_line_ip = first_footprint_inside_detection_ip; - const bool first_attention_stop_line_valid = true; + const auto first_attention_stopline_ip = first_footprint_inside_detection_ip; + const bool first_attention_stopline_valid = true; // (4) pass judge line position on interpolated path const double velocity = planner_data->current_velocity->twist.linear.x; @@ -367,52 +367,52 @@ std::optional generateIntersectionStopLines( static_cast(first_footprint_attention_centerline_ip); // (5) stuck vehicle stop line - int stuck_stop_line_ip_int = 0; - bool stuck_stop_line_valid = true; + int stuck_stopline_ip_int = 0; + bool stuck_stopline_valid = true; if (use_stuck_stopline) { // NOTE: when ego vehicle is approaching detection area and already passed // first_conflicting_area, this could be null. - const auto stuck_stop_line_idx_ip_opt = getFirstPointInsidePolygonByFootprint( + const auto stuck_stopline_idx_ip_opt = getFirstPointInsidePolygonByFootprint( first_conflicting_area, interpolated_path_info, local_footprint, baselink2front); - if (!stuck_stop_line_idx_ip_opt) { - stuck_stop_line_valid = false; - stuck_stop_line_ip_int = 0; + if (!stuck_stopline_idx_ip_opt) { + stuck_stopline_valid = false; + stuck_stopline_ip_int = 0; } else { - stuck_stop_line_ip_int = stuck_stop_line_idx_ip_opt.value() - stop_line_margin_idx_dist; + stuck_stopline_ip_int = stuck_stopline_idx_ip_opt.value() - stopline_margin_idx_dist; } } else { - stuck_stop_line_ip_int = - std::get<0>(lane_interval_ip) - (stop_line_margin_idx_dist + base2front_idx_dist); + stuck_stopline_ip_int = + std::get<0>(lane_interval_ip) - (stopline_margin_idx_dist + base2front_idx_dist); } - if (stuck_stop_line_ip_int < 0) { - stuck_stop_line_valid = false; + if (stuck_stopline_ip_int < 0) { + stuck_stopline_valid = false; } - const auto stuck_stop_line_ip = static_cast(std::max(0, stuck_stop_line_ip_int)); + const auto stuck_stopline_ip = static_cast(std::max(0, stuck_stopline_ip_int)); struct IntersectionStopLinesTemp { size_t closest_idx{0}; - size_t stuck_stop_line{0}; - size_t default_stop_line{0}; - size_t first_attention_stop_line{0}; - size_t occlusion_peeking_stop_line{0}; + size_t stuck_stopline{0}; + size_t default_stopline{0}; + size_t first_attention_stopline{0}; + size_t occlusion_peeking_stopline{0}; size_t pass_judge_line{0}; size_t occlusion_wo_tl_pass_judge_line{0}; }; - IntersectionStopLinesTemp intersection_stop_lines_temp; - std::list> stop_lines = { - {&closest_idx_ip, &intersection_stop_lines_temp.closest_idx}, - {&stuck_stop_line_ip, &intersection_stop_lines_temp.stuck_stop_line}, - {&default_stop_line_ip, &intersection_stop_lines_temp.default_stop_line}, - {&first_attention_stop_line_ip, &intersection_stop_lines_temp.first_attention_stop_line}, - {&occlusion_peeking_line_ip, &intersection_stop_lines_temp.occlusion_peeking_stop_line}, - {&pass_judge_line_ip, &intersection_stop_lines_temp.pass_judge_line}, + IntersectionStopLinesTemp intersection_stoplines_temp; + std::list> stoplines = { + {&closest_idx_ip, &intersection_stoplines_temp.closest_idx}, + {&stuck_stopline_ip, &intersection_stoplines_temp.stuck_stopline}, + {&default_stopline_ip, &intersection_stoplines_temp.default_stopline}, + {&first_attention_stopline_ip, &intersection_stoplines_temp.first_attention_stopline}, + {&occlusion_peeking_line_ip, &intersection_stoplines_temp.occlusion_peeking_stopline}, + {&pass_judge_line_ip, &intersection_stoplines_temp.pass_judge_line}, {&occlusion_wo_tl_pass_judge_line_ip, - &intersection_stop_lines_temp.occlusion_wo_tl_pass_judge_line}}; - stop_lines.sort( + &intersection_stoplines_temp.occlusion_wo_tl_pass_judge_line}}; + stoplines.sort( [](const auto & it1, const auto & it2) { return *(std::get<0>(it1)) < *(std::get<0>(it2)); }); - for (const auto & [stop_idx_ip, stop_idx] : stop_lines) { + for (const auto & [stop_idx_ip, stop_idx] : stoplines) { const auto & insert_point = path_ip.points.at(*stop_idx_ip).point.pose; const auto insert_idx = insertPointIndex( insert_point, original_path, planner_data->ego_nearest_dist_threshold, @@ -423,32 +423,32 @@ std::optional generateIntersectionStopLines( *stop_idx = insert_idx.value(); } if ( - intersection_stop_lines_temp.occlusion_peeking_stop_line < - intersection_stop_lines_temp.default_stop_line) { - intersection_stop_lines_temp.occlusion_peeking_stop_line = - intersection_stop_lines_temp.default_stop_line; + intersection_stoplines_temp.occlusion_peeking_stopline < + intersection_stoplines_temp.default_stopline) { + intersection_stoplines_temp.occlusion_peeking_stopline = + intersection_stoplines_temp.default_stopline; } - IntersectionStopLines intersection_stop_lines; - intersection_stop_lines.closest_idx = intersection_stop_lines_temp.closest_idx; - if (stuck_stop_line_valid) { - intersection_stop_lines.stuck_stop_line = intersection_stop_lines_temp.stuck_stop_line; + IntersectionStopLines intersection_stoplines; + intersection_stoplines.closest_idx = intersection_stoplines_temp.closest_idx; + if (stuck_stopline_valid) { + intersection_stoplines.stuck_stopline = intersection_stoplines_temp.stuck_stopline; } - if (default_stop_line_valid) { - intersection_stop_lines.default_stop_line = intersection_stop_lines_temp.default_stop_line; + if (default_stopline_valid) { + intersection_stoplines.default_stopline = intersection_stoplines_temp.default_stopline; } - if (first_attention_stop_line_valid) { - intersection_stop_lines.first_attention_stop_line = - intersection_stop_lines_temp.first_attention_stop_line; + if (first_attention_stopline_valid) { + intersection_stoplines.first_attention_stopline = + intersection_stoplines_temp.first_attention_stopline; } if (occlusion_peeking_line_valid) { - intersection_stop_lines.occlusion_peeking_stop_line = - intersection_stop_lines_temp.occlusion_peeking_stop_line; + intersection_stoplines.occlusion_peeking_stopline = + intersection_stoplines_temp.occlusion_peeking_stopline; } - intersection_stop_lines.pass_judge_line = intersection_stop_lines_temp.pass_judge_line; - intersection_stop_lines.occlusion_wo_tl_pass_judge_line = - intersection_stop_lines_temp.occlusion_wo_tl_pass_judge_line; - return intersection_stop_lines; + intersection_stoplines.pass_judge_line = intersection_stoplines_temp.pass_judge_line; + intersection_stoplines.occlusion_wo_tl_pass_judge_line = + intersection_stoplines_temp.occlusion_wo_tl_pass_judge_line; + return intersection_stoplines; } std::optional getFirstPointInsidePolygon( @@ -537,30 +537,30 @@ getFirstPointInsidePolygons( std::optional generateStuckStopLine( const lanelet::CompoundPolygon3d & conflicting_area, const std::shared_ptr & planner_data, - const InterpolatedPathInfo & interpolated_path_info, const double stop_line_margin, + const InterpolatedPathInfo & interpolated_path_info, const double stopline_margin, const bool use_stuck_stopline, autoware_auto_planning_msgs::msg::PathWithLaneId * original_path) { const auto & path_ip = interpolated_path_info.path; const double ds = interpolated_path_info.ds; const auto & lane_interval_ip = interpolated_path_info.lane_id_interval.value(); const auto lane_interval_ip_start = std::get<0>(lane_interval_ip); - size_t stuck_stop_line_idx_ip = 0; + size_t stuck_stopline_idx_ip = 0; if (use_stuck_stopline) { - stuck_stop_line_idx_ip = lane_interval_ip_start; + stuck_stopline_idx_ip = lane_interval_ip_start; } else { - const auto stuck_stop_line_idx_ip_opt = + const auto stuck_stopline_idx_ip_opt = getFirstPointInsidePolygon(path_ip, lane_interval_ip, conflicting_area); - if (!stuck_stop_line_idx_ip_opt) { + if (!stuck_stopline_idx_ip_opt) { return std::nullopt; } - stuck_stop_line_idx_ip = stuck_stop_line_idx_ip_opt.value(); + stuck_stopline_idx_ip = stuck_stopline_idx_ip_opt.value(); } - const int stop_line_margin_idx_dist = std::ceil(stop_line_margin / ds); + const int stopline_margin_idx_dist = std::ceil(stopline_margin / ds); const int base2front_idx_dist = std::ceil(planner_data->vehicle_info_.max_longitudinal_offset_m / ds); const size_t insert_idx_ip = static_cast(std::max( - static_cast(stuck_stop_line_idx_ip) - 1 - stop_line_margin_idx_dist - base2front_idx_dist, + static_cast(stuck_stopline_idx_ip) - 1 - stopline_margin_idx_dist - base2front_idx_dist, 0)); const auto & insert_point = path_ip.points.at(insert_idx_ip).point.pose; return insertPointIndex( @@ -695,8 +695,8 @@ IntersectionLanelets getObjectiveLanelets( if (const auto tl_reg_elems = assigned_lanelet.regulatoryElementsAs(); tl_reg_elems.size() != 0) { const auto tl_reg_elem = tl_reg_elems.front(); - const auto stop_line_opt = tl_reg_elem->stopLine(); - if (!!stop_line_opt) has_traffic_light = true; + const auto stopline_opt = tl_reg_elem->stopLine(); + if (!!stopline_opt) has_traffic_light = true; } // for low priority lane @@ -744,7 +744,7 @@ IntersectionLanelets getObjectiveLanelets( // final objective lanelets lanelet::ConstLanelets detection_lanelets; lanelet::ConstLanelets conflicting_ex_ego_lanelets; - // conflicting lanes is necessary to get stop_line for stuck vehicle + // conflicting lanes is necessary to get stopline for stuck vehicle for (auto && conflicting_lanelet : conflicting_lanelets) { if (!lanelet::utils::contains(ego_lanelets, conflicting_lanelet)) conflicting_ex_ego_lanelets.push_back(conflicting_lanelet); @@ -836,31 +836,31 @@ IntersectionLanelets getObjectiveLanelets( for (const auto & original_attention_lanelet_seq : original_attention_lanelet_sequences) { // NOTE: in mergeLaneletsByTopologicalSort(), sub_ids are empty checked, so it is ensured that // back() exists. - std::optional stop_line{std::nullopt}; + std::optional stopline{std::nullopt}; for (auto it = original_attention_lanelet_seq.rbegin(); it != original_attention_lanelet_seq.rend(); ++it) { const auto traffic_lights = it->regulatoryElementsAs(); for (const auto & traffic_light : traffic_lights) { - const auto stop_line_opt = traffic_light->stopLine(); - if (!stop_line_opt) continue; - stop_line = stop_line_opt.get(); + const auto stopline_opt = traffic_light->stopLine(); + if (!stopline_opt) continue; + stopline = stopline_opt.get(); break; } - if (stop_line) break; + if (stopline) break; } - result.attention_stop_lines_.push_back(stop_line); + result.attention_stoplines_.push_back(stopline); } result.attention_non_preceding_ = std::move(detection_lanelets); for (unsigned i = 0; i < result.attention_non_preceding_.size(); ++i) { - std::optional stop_line = std::nullopt; + std::optional stopline = std::nullopt; const auto & ll = result.attention_non_preceding_.at(i); const auto traffic_lights = ll.regulatoryElementsAs(); for (const auto & traffic_light : traffic_lights) { - const auto stop_line_opt = traffic_light->stopLine(); - if (!stop_line_opt) continue; - stop_line = stop_line_opt.get(); + const auto stopline_opt = traffic_light->stopLine(); + if (!stopline_opt) continue; + stopline = stopline_opt.get(); } - result.attention_non_preceding_stop_lines_.push_back(stop_line); + result.attention_non_preceding_stoplines_.push_back(stopline); } result.conflicting_ = std::move(conflicting_ex_ego_lanelets); result.adjacent_ = planning_utils::getConstLaneletsFromIds(lanelet_map_ptr, associative_ids); @@ -1317,7 +1317,7 @@ TimeDistanceArray calcIntersectionPassingTime( const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const std::shared_ptr & planner_data, const lanelet::Id lane_id, const std::set & associative_ids, const size_t closest_idx, - const size_t last_intersection_stop_line_candidate_idx, const double time_delay, + const size_t last_intersection_stopline_candidate_idx, const double time_delay, const double intersection_velocity, const double minimum_ego_velocity, const bool use_upstream_velocity, const double minimum_upstream_velocity, tier4_debug_msgs::msg::Float64MultiArrayStamped * debug_ttc_array) @@ -1329,7 +1329,7 @@ TimeDistanceArray calcIntersectionPassingTime( // crop intersection part of the path, and set the reference velocity to intersection_velocity // for ego's ttc PathWithLaneId reference_path; - std::optional upstream_stop_line{std::nullopt}; + std::optional upstream_stopline{std::nullopt}; for (size_t i = 0; i < path.points.size() - 1; ++i) { auto reference_point = path.points.at(i); // assume backward velocity is current ego velocity @@ -1337,11 +1337,11 @@ TimeDistanceArray calcIntersectionPassingTime( reference_point.point.longitudinal_velocity_mps = current_velocity; } if ( - i > last_intersection_stop_line_candidate_idx && + i > last_intersection_stopline_candidate_idx && std::fabs(reference_point.point.longitudinal_velocity_mps) < std::numeric_limits::epsilon() && - !upstream_stop_line) { - upstream_stop_line = i; + !upstream_stopline) { + upstream_stopline = i; } if (!use_upstream_velocity) { reference_point.point.longitudinal_velocity_mps = intersection_velocity; @@ -1376,23 +1376,23 @@ TimeDistanceArray calcIntersectionPassingTime( time_distance_array.emplace_back(passing_time, dist_sum); // NOTE: `reference_path` is resampled in `reference_smoothed_path`, so - // `last_intersection_stop_line_candidate_idx` makes no sense + // `last_intersection_stopline_candidate_idx` makes no sense const auto smoothed_path_closest_idx = motion_utils::findFirstNearestIndexWithSoftConstraints( smoothed_reference_path.points, path.points.at(closest_idx).point.pose, planner_data->ego_nearest_dist_threshold, planner_data->ego_nearest_yaw_threshold); - const std::optional upstream_stop_line_idx_opt = [&]() -> std::optional { - if (upstream_stop_line) { - const auto upstream_stop_line_point = path.points.at(upstream_stop_line.value()).point.pose; + const std::optional upstream_stopline_idx_opt = [&]() -> std::optional { + if (upstream_stopline) { + const auto upstream_stopline_point = path.points.at(upstream_stopline.value()).point.pose; return motion_utils::findFirstNearestIndexWithSoftConstraints( - smoothed_reference_path.points, upstream_stop_line_point, + smoothed_reference_path.points, upstream_stopline_point, planner_data->ego_nearest_dist_threshold, planner_data->ego_nearest_yaw_threshold); } else { return std::nullopt; } }(); - const bool has_upstream_stopline = upstream_stop_line_idx_opt.has_value(); - const size_t upstream_stopline_ind = upstream_stop_line_idx_opt.value_or(0); + const bool has_upstream_stopline = upstream_stopline_idx_opt.has_value(); + const size_t upstream_stopline_ind = upstream_stopline_idx_opt.value_or(0); for (size_t i = smoothed_path_closest_idx; i < smoothed_reference_path.points.size() - 1; ++i) { const auto & p1 = smoothed_reference_path.points.at(i); @@ -1613,22 +1613,22 @@ std::optional generatePathLanelets( return path_lanelets; } -void TargetObject::calc_dist_to_stop_line() +void TargetObject::calc_dist_to_stopline() { - if (!attention_lanelet || !stop_line) { + if (!attention_lanelet || !stopline) { return; } const auto attention_lanelet_val = attention_lanelet.value(); const auto object_arc_coords = lanelet::utils::getArcCoordinates( {attention_lanelet_val}, object.kinematics.initial_pose_with_covariance.pose); - const auto stop_line_val = stop_line.value(); + const auto stopline_val = stopline.value(); geometry_msgs::msg::Pose stopline_center; - stopline_center.position.x = (stop_line_val.front().x() + stop_line_val.back().x()) / 2.0; - stopline_center.position.y = (stop_line_val.front().y() + stop_line_val.back().y()) / 2.0; - stopline_center.position.z = (stop_line_val.front().z() + stop_line_val.back().z()) / 2.0; + stopline_center.position.x = (stopline_val.front().x() + stopline_val.back().x()) / 2.0; + stopline_center.position.y = (stopline_val.front().y() + stopline_val.back().y()) / 2.0; + stopline_center.position.z = (stopline_val.front().z() + stopline_val.back().z()) / 2.0; const auto stopline_arc_coords = lanelet::utils::getArcCoordinates({attention_lanelet_val}, stopline_center); - dist_to_stop_line = (stopline_arc_coords.length - object_arc_coords.length); + dist_to_stopline = (stopline_arc_coords.length - object_arc_coords.length); } } // namespace util diff --git a/planning/behavior_velocity_intersection_module/src/util.hpp b/planning/behavior_velocity_intersection_module/src/util.hpp index 79ccf629d69d4..8d0e673fc931e 100644 --- a/planning/behavior_velocity_intersection_module/src/util.hpp +++ b/planning/behavior_velocity_intersection_module/src/util.hpp @@ -65,7 +65,7 @@ IntersectionLanelets getObjectiveLanelets( std::optional generateStuckStopLine( const lanelet::CompoundPolygon3d & first_conflicting_area, const std::shared_ptr & planner_data, - const InterpolatedPathInfo & interpolated_path_info, const double stop_line_margin, + const InterpolatedPathInfo & interpolated_path_info, const double stopline_margin, const bool use_stuck_stopline, autoware_auto_planning_msgs::msg::PathWithLaneId * original_path); std::optional generateIntersectionStopLines( @@ -74,7 +74,7 @@ std::optional generateIntersectionStopLines( const lanelet::ConstLineString2d & first_attention_lane_centerline, const std::shared_ptr & planner_data, const InterpolatedPathInfo & interpolated_path_info, const bool use_stuck_stopline, - const double stop_line_margin, const double max_accel, const double max_jerk, + const double stopline_margin, const double max_accel, const double max_jerk, const double delay_response_time, const double peeking_offset, autoware_auto_planning_msgs::msg::PathWithLaneId * original_path); @@ -152,7 +152,7 @@ TimeDistanceArray calcIntersectionPassingTime( const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const std::shared_ptr & planner_data, const lanelet::Id lane_id, const std::set & associative_ids, const size_t closest_idx, - const size_t last_intersection_stop_line_candidate_idx, const double time_delay, + const size_t last_intersection_stopline_candidate_idx, const double time_delay, const double intersection_velocity, const double minimum_ego_velocity, const bool use_upstream_velocity, const double minimum_upstream_velocity, tier4_debug_msgs::msg::Float64MultiArrayStamped * debug_ttc_array); diff --git a/planning/behavior_velocity_intersection_module/src/util_type.hpp b/planning/behavior_velocity_intersection_module/src/util_type.hpp index a324cce06c18f..3c7ba3041b0bd 100644 --- a/planning/behavior_velocity_intersection_module/src/util_type.hpp +++ b/planning/behavior_velocity_intersection_module/src/util_type.hpp @@ -79,9 +79,9 @@ struct IntersectionLanelets { return is_prioritized_ ? attention_non_preceding_ : attention_; } - const std::vector> & attention_stop_lines() const + const std::vector> & attention_stoplines() const { - return is_prioritized_ ? attention_non_preceding_stop_lines_ : attention_stop_lines_; + return is_prioritized_ ? attention_non_preceding_stoplines_ : attention_stoplines_; } const lanelet::ConstLanelets & conflicting() const { return conflicting_; } const lanelet::ConstLanelets & adjacent() const { return adjacent_; } @@ -121,11 +121,11 @@ struct IntersectionLanelets lanelet::ConstLanelets attention_; // topologically merged lanelets std::vector> - attention_stop_lines_; // the stop lines for each attention_ lanelets + attention_stoplines_; // the stop lines for each attention_ lanelets lanelet::ConstLanelets attention_non_preceding_; std::vector> - attention_non_preceding_stop_lines_; // the stop lines for each attention_non_preceding_ - // lanelets + attention_non_preceding_stoplines_; // the stop lines for each attention_non_preceding_ + // lanelets lanelet::ConstLanelets conflicting_; lanelet::ConstLanelets adjacent_; lanelet::ConstLanelets occlusion_attention_; // topologically merged lanelets @@ -151,13 +151,13 @@ struct IntersectionStopLines // NOTE: for baselink size_t closest_idx{0}; // NOTE: null if path does not conflict with first_conflicting_area - std::optional stuck_stop_line{std::nullopt}; - // NOTE: null if path is over map stop_line OR its value is calculated negative - std::optional default_stop_line{std::nullopt}; + std::optional stuck_stopline{std::nullopt}; + // NOTE: null if path is over map stopline OR its value is calculated negative + std::optional default_stopline{std::nullopt}; // NOTE: null if the index is calculated negative - std::optional first_attention_stop_line{std::nullopt}; + std::optional first_attention_stopline{std::nullopt}; // NOTE: null if footprints do not change from outside to inside of detection area - std::optional occlusion_peeking_stop_line{std::nullopt}; + std::optional occlusion_peeking_stopline{std::nullopt}; // if the value is calculated negative, its value is 0 size_t pass_judge_line{0}; size_t occlusion_wo_tl_pass_judge_line{0}; @@ -183,9 +183,9 @@ struct TargetObject { autoware_auto_perception_msgs::msg::PredictedObject object; std::optional attention_lanelet{std::nullopt}; - std::optional stop_line{std::nullopt}; - std::optional dist_to_stop_line{std::nullopt}; - void calc_dist_to_stop_line(); + std::optional stopline{std::nullopt}; + std::optional dist_to_stopline{std::nullopt}; + void calc_dist_to_stopline(); }; struct TargetObjects