Package Summary
Tags | No category tags. |
Version | 0.43.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-04-03 |
Dev Status | UNMAINTAINED |
CI status | No Continuous Integration |
Released | UNRELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- Satoshi Ota
- Tomoya Kimura
- Shumpei Wakabayashi
- Takayuki Murooka
- Kyoichi Sugahara
- Mamoru Sobue
- Yuki Takagi
Authors
- Satoshi Ota
Crosswalk
Role
This module judges whether the ego should stop in front of the crosswalk in order to provide safe passage for crosswalk users, such as pedestrians and bicycles, based on the objects’ behavior and surround traffic.
Flowchart
@startuml
title modifyPathVelocity
start
:getPathEndPointsOnCrosswalk;
group apply slow down
:applySlowDownByLanleet2Map;
:applySlowDownByOcclusion;
end group
group calculate stop pose
:getDefaultStopPose;
:resamplePath;
:checkStopForCrosswalkUsers;
:checkStopForStuckVehicles;
end group
group apply stop
:getNearestStopFactor;
:setSafe;
:setDistanceToStop;
if (isActivated() is True?) then (yes)
:planGo;
else (no)
:planStop;
endif
end group
stop
@enduml
@startuml
title checkStopForCrosswalkUsers
start
group calculate the candidate stop
:pick the closest stop point against the pedestrians and stop point on map as the preferred stop;
if (the weak brake distance is closer than the preferred stop?) then (yes)
:plan to stop at the preferred stop;
else (no)
if (the weak brake distance is closer than the limit stop position against the nearest pedestrian?) then (yes)
:plan to stop by the weak brake distance;
else (no)
:plan to stop at the limit stop position against the nearest pedestrian;
endif
endif
end group
group check if the candidate stop pose is acceptable for braking distance
if (the stop pose candidate is closer than the acceptable stop dist?) then (yes)
:abort to stop.;
else (no)
:plan to stop at the candidate stop pose;
endif
end group
stop
@enduml
Features
Yield the Way to the Pedestrians
Target Object
The crosswalk module handles objects of the types defined by the following parameters in the object_filtering.target_object
namespace.
Parameter | Unit | Type | Description |
---|---|---|---|
unknown |
[-] | bool | whether to look and stop by UNKNOWN objects |
pedestrian |
[-] | bool | whether to look and stop by PEDESTRIAN objects |
bicycle |
[-] | bool | whether to look and stop by BICYCLE objects |
motorcycle |
[-] | bool | whether to look and stop by MOTORCYCLE objects |
In order to handle the crosswalk users crossing the neighborhood but outside the crosswalk, the crosswalk module creates an attention area around the crosswalk, shown as the yellow polygon in the figure. If the object’s predicted path collides with the attention area, the object will be targeted for yield.
The neighborhood is defined by the following parameter in the object_filtering.target_object
namespace.
Parameter | Unit | Type | Description |
---|---|---|---|
crosswalk_attention_range |
[m] | double | the detection area is defined as -X meters before the crosswalk to +X meters behind the crosswalk |
Stop Position
First of all, stop_distance_from_object [m]
is always kept at least between the ego and the target object for safety.
When the stop line exists in the lanelet map, the stop position is calculated based on the line.
When the stop line does NOT exist in the lanelet map, the stop position is calculated by keeping stop_distance_from_crosswalk [m]
between the ego and the crosswalk.
As an exceptional case, if a pedestrian (or bicycle) is crossing wide crosswalks seen in scramble intersections, and the pedestrian position is more than far_object_threshold
meters away from the stop line, the actual stop position is determined by stop_distance_from_object
and pedestrian position, not at the stop line.
In the stop_position
namespace, the following parameters are defined.
Parameter | Type | Description | |
---|---|---|---|
stop_position_threshold |
[m] | double | If the ego vehicle has stopped near the stop line than this value, this module assumes itself to have achieved yielding. |
stop_distance_from_crosswalk |
[m] | double | make stop line away from crosswalk for the Lanelet2 map with no explicit stop lines |
far_object_threshold |
[m] | double | If objects cross X meters behind the stop line, the stop position is determined according to the object position (stop_distance_from_object meters before the object) for the case where the crosswalk width is very wide |
stop_distance_from_object |
[m] | double | the vehicle decelerates to be able to stop in front of object with margin |
Yield decision
The module makes a decision to yield only when the pedestrian traffic light is GREEN or UNKNOWN. The decision is based on the following variables, along with the calculation of the collision point.
- Time-To-Collision (TTC): The time for the ego to reach the virtual collision point.
- Time-To-Vehicle (TTV): The time for the object to reach the virtual collision point.
We classify ego behavior at crosswalks into three categories according to the relative relationship between TTC and TTV [1].
- A. TTC » TTV: The object will pass early enough than the ego reach the collision point.
- No stop planning.
- B. TTC ≒ TTV: There is a risk of collision.
- Stop point is inserted in the ego’s path.
- C. TTC « TTV: The ego will pass early enough than the object reach the collision point.
- No stop planning.
The following figure shows the decision result for each TTC and TTV with the parameters, ego_pass_first_margin_x
is {0}
, ego_pass_first_margin_y
is {4}
, ego_pass_later_margin_x
is {0}
, and ego_pass_later_margin_y
is {13}
.
If the red signal is indicating to the corresponding crosswalk, the ego do not yield against the pedestrians.
In the pass_judge
namespace, the following parameters are defined.
Parameter | Type | Description | |
---|---|---|---|
ego_pass_first_margin_x |
[[s]] | double | time to collision margin vector for ego pass first situation (the module judges that ego don’t have to stop at TTC + MARGIN < TTV condition) |
ego_pass_first_margin_y |
[[s]] | double | time to vehicle margin vector for ego pass first situation (the module judges that ego don’t have to stop at TTC + MARGIN < TTV condition) |
ego_pass_first_additional_margin |
[s] | double | additional time margin for ego pass first situation to suppress chattering |
ego_pass_later_margin_x |
[[s]] | double | time to vehicle margin vector for object pass first situation (the module judges that ego don’t have to stop at TTV + MARGIN < TTC condition) |
ego_pass_later_margin_y |
[[s]] | double | time to collision margin vector for object pass first situation (the module judges that ego don’t have to stop at TTV + MARGIN < TTC condition) |
ego_pass_later_additional_margin |
[s] | double | additional time margin for object pass first situation to suppress chattering |
Smooth Yield Decision
If the object is stopped near the crosswalk but has no intention of walking, a situation can arise in which the ego continues to yield the right-of-way to the object. To prevent such a deadlock situation, the ego will cancel yielding depending on the situation.
For the object stopped around the crosswalk but has no intention to walk (*1), after the ego has keep stopping to yield for a specific time (*2), the ego cancels the yield and starts driving.
*1:
The time is calculated by the interpolation of distance between the object and crosswalk with distance_set_for_no_intention_to_walk
and timeout_set_for_no_intention_to_walk
.
In the pass_judge
namespace, the following parameters are defined.
Parameter | Type | Description | |
---|---|---|---|
distance_set_for_no_intention_to_walk |
[[m]] | double | key sets to calculate the timeout for no intention to walk with interpolation |
timeout_set_for_no_intention_to_walk |
[[s]] | double | value sets to calculate the timeout for no intention to walk with interpolation |
*2:
In the pass_judge
namespace, the following parameters are defined.
Parameter | Type | Description | |
---|---|---|---|
timeout_ego_stop_for_yield |
[s] | double | If the ego maintains the stop for this amount of time, then the ego proceeds, assuming it has stopped long time enough. |
New Object Handling
Due to the perception’s limited performance where the tree or poll is recognized as a pedestrian or the tracking failure in the crowd or occlusion, even if the surrounding environment does not change, the new pedestrian (= the new ID’s pedestrian) may suddenly appear unexpectedly. If this happens while the ego is going to pass the crosswalk, the ego will stop suddenly.
To deal with this issue, the option disable_yield_for_new_stopped_object
is prepared.
If true is set, the yield decisions around the crosswalk with a traffic light will ignore the new stopped object.
In the pass_judge
namespace, the following parameters are defined.
Parameter | Type | Description | |
---|---|---|---|
disable_yield_for_new_stopped_object |
[-] | bool | If set to true, the new stopped object will be ignored around the crosswalk with a traffic light |
Stuck Prevention on the Crosswalk
The feature will make the ego not to stop on the crosswalk. When there is a low-speed or stopped vehicle ahead of the crosswalk, and there is not enough space between the crosswalk and the vehicle, the crosswalk module plans to stop before the crosswalk even if there are no pedestrians or bicycles.
min_acc
, min_jerk
, and max_jerk
are met. If the ego cannot stop before the crosswalk with these parameters, the stop position will move forward.
In the stuck_vehicle
namespace, the following parameters are defined.
Parameter | Unit | Type | Description |
---|---|---|---|
stuck_vehicle_velocity |
[m/s] | double | maximum velocity threshold whether the target vehicle is stopped or not |
max_stuck_vehicle_lateral_offset |
[m] | double | maximum lateral offset of the target vehicle position |
required_clearance |
[m] | double | clearance to be secured between the ego and the ahead vehicle |
min_acc |
[m/ss] | double | minimum acceleration to stop |
min_jerk |
[m/sss] | double | minimum jerk to stop |
max_jerk |
[m/sss] | double | maximum jerk to stop |
Safety Slow Down Behavior
In the current autoware implementation, if no target object is detected around a crosswalk, the ego vehicle will not slow down for the crosswalk. However, it may be desirable to slow down in situations, for example, where there are blind spots. Such a situation can be handled by setting some tags to the related crosswalk as instructed in the lanelet2_format_extension.md document.
Parameter | Type | Description | |
---|---|---|---|
slow_velocity |
[m/s] | double | target vehicle velocity when module receive slow down command from FOA |
max_slow_down_jerk |
[m/sss] | double | minimum jerk deceleration for safe brake |
max_slow_down_accel |
[m/ss] | double | minimum accel deceleration for safe brake |
no_relax_velocity |
[m/s] | double | if the current velocity is less than X m/s, ego always stops at the stop position(not relax deceleration constraints) |
Occlusion
This feature makes ego slow down for a crosswalk that is occluded.
Occlusion of the crosswalk is determined using the occupancy grid.
An occlusion is a square of size min_size
of occluded cells
(i.e., their values are between free_space_max
and occupied_min
)
of size min_size
.
If an occlusion is found within range of the crosswalk,
then the velocity limit at the crosswalk is set to slow_down_velocity
(or more to not break limits set by max_slow_down_jerk
and max_slow_down_accel
).
The range is calculated from the intersection between the ego path and the crosswalk and is equal to the time taken by ego to reach the crosswalk times the occluded_object_velocity
.
This range is meant to be large when ego is far from the crosswalk and small when ego is close.
In order to avoid flickering decisions, a time buffer can be used such that the decision to add (or remove) the slow down is only taken
after an occlusion is detected (or not detected) for a consecutive time defined by the time_buffer
parameter.
To ignore occlusions when the crosswalk has a traffic light, ignore_with_traffic_light
should be set to true.
To ignore temporary occlusions caused by moving objects,
ignore_behind_predicted_objects
should be set to true.
By default, occlusions behind an object with velocity higher than ignore_velocity_thresholds.default
are ignored.
This velocity threshold can be specified depending on the object type by specifying the object class label and velocity threshold in the parameter lists ignore_velocity_thresholds.custom_labels
and ignore_velocity_thresholds.custom_thresholds
.
To inflate the masking behind objects, their footprint can be made bigger using extra_predicted_objects_size
.
Parameter | Unit | Type | Description |
---|---|---|---|
enable |
[-] | bool | if true, ego will slow down around crosswalks that are occluded |
occluded_object_velocity |
[m/s] | double | assumed velocity of objects that may come out of the occluded space |
slow_down_velocity |
[m/s] | double | slow down velocity |
time_buffer |
[s] | double | consecutive time with/without an occlusion to add/remove the slowdown |
min_size |
[m] | double | minimum size of an occlusion (square side size) |
free_space_max |
[-] | double | maximum value of a free space cell in the occupancy grid |
occupied_min |
[-] | double | minimum value of an occupied cell in the occupancy grid |
ignore_with_traffic_light |
[-] | bool | if true, occlusions at crosswalks with traffic lights are ignored |
ignore_behind_predicted_objects |
[-] | bool | if true, occlusions behind predicted objects are ignored |
ignore_velocity_thresholds.default |
[m/s] | double | occlusions are only ignored behind objects with a higher or equal velocity |
ignore_velocity_thresholds.custom_labels |
[-] | string list | labels for which to define a non-default velocity threshold (see autoware_perception_msgs::msg::ObjectClassification for all the labels) |
ignore_velocity_thresholds.custom_thresholds |
[-] | double list | velocities of the custom labels |
extra_predicted_objects_size |
[m] | double | extra size added to the objects for masking the occlusions |
Others
In the common
namespace, the following parameters are defined.
Parameter | Unit | Type | Description |
---|---|---|---|
show_processing_time |
[-] | bool | whether to show processing time |
traffic_light_state_timeout |
[s] | double | timeout threshold for traffic light signal |
enable_rtc |
[-] | bool | if true, the scene modules should be approved by (request to cooperate)rtc function. if false, the module can be run without approval from rtc. |
Known Issues
- The yield decision may be sometimes aggressive or conservative depending on the case.
- The main reason is that the crosswalk module does not know the ego’s position in the future. The detailed ego’s position will be determined after the whole planning.
- Currently the module assumes that the ego will move with a constant velocity.
Debugging
Visualization of debug markers
/planning/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/debug/crosswalk
shows the following markers.
- Yellow polygons
- Ego footprints’ polygon to calculate the collision check.
- Pink polygons
- Object footprints’ polygon to calculate the collision check.
- The color of crosswalks
- Considering the traffic light’s color, red means the target crosswalk, and white means the ignored crosswalk.
- Texts
- It shows the module ID, TTC, TTV, and the module state.
Visualization of Time-To-Collision
ros2 run autoware_behavior_velocity_crosswalk_module time_to_collision_plotter.py
enables you to visualize the following figure of the ego and pedestrian’s time to collision.
The label of each plot is <crosswalk module id>-<pedestrian uuid>
.
Trouble Shooting
Behavior
- Q. The ego stopped around the crosswalk even though there were no crosswalk user objects.
- A. See Stuck Vehicle Detection.
- Q. The crosswalk virtual wall suddenly appeared resulting in the sudden stop.
- A. There may be a crosswalk user started moving when the ego was close to the crosswalk.
- Q. The crosswalk module decides to stop even when the pedestrian traffic light is red.
- A. The lanelet map may be incorrect. The pedestrian traffic light and the crosswalk have to be related.
- Q. In the planning simulation, the crosswalk module does the yield decision to stop on all the crosswalks.
- A. This is because the pedestrian traffic light is unknown by default. In this case, the crosswalk does the yield decision for safety.
Parameter Tuning
- Q. The ego’s yield behavior is too conservative.
- A. Tune
ego_pass_later_margin
described in Yield Decision
- A. Tune
- Q. The ego’s yield behavior is too aggressive.
- A. Tune
ego_pass_later_margin
described in Yield Decision
- A. Tune
References/External links
[1] 佐藤 みなみ, 早坂 祥一, 清水 政行, 村野 隆彦, 横断歩行者に対するドライバのリスク回避行動のモデル化, 自動車技術会論文集, 2013, 44 巻, 3 号, p. 931-936.
Changelog for package autoware_behavior_velocity_crosswalk_module
0.43.0 (2025-03-21)
- Merge remote-tracking branch 'origin/main' into chore/bump-version-0.43
- chore: rename from [autoware.universe]{.title-ref} to [autoware_universe]{.title-ref} (#10306)
- fix(behavior_velocity_planner): planning factor integration
(#10292)
- fix: blind_spot
- fix: crosswalk
- fix: detection_area
- fix: intersection
- fix: no_drivable_lane
- fix: no_stopping_area
- fix: run_out
- fix: stop_line
- fix: traffic_light
- fix: virtual_traffic_light
* fix: walk_way ---------
- feat(Autoware_planning_factor_interface): replace tier4_msgs with autoware_internal_msgs (#10204)
- Contributors: Hayato Mizushima, Satoshi OTA, Yutaka Kondo, 心刚
0.42.0 (2025-03-03)
- Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base
- feat(autoware_utils): replace autoware_universe_utils with autoware_utils (#10191)
- feat(autoware_objects_of_interest_marker_interface): replace autoware_universe_utils with autoware_utils (#10174)
- feat!: replace tier4_planning_msgs/PathWithLaneId with autoware_internal_planning_msgs/PathWithLaneId (#10023)
- feat(planning_test_manager): abstract message-specific functions
(#9882)
- abstract message-specific functions
- include necessary header
- adapt velocity_smoother to new test manager
- adapt behavior_velocity_planner to new test manager
- adapt path_optimizer to new test manager
- fix output subscription
- adapt behavior_path_planner to new test manager
- adapt scenario_selector to new test manager
- adapt freespace_planner to new test manager
- adapt planning_validator to new test manager
- adapt obstacle_stop_planner to new test manager
- adapt obstacle_cruise_planner to new test manager
- disable test for freespace_planner
- adapt behavior_velocity_crosswalk_module to new test manager
- adapt behavior_path_lane_change_module to new test manager
- adapt behavior_path_avoidance_by_lane_change_module to new test manager
- adapt behavior_path_dynamic_obstacle_avoidance_module to new test manager
- adapt behavior_path_external_request_lane_change_module to new test manager
- adapt behavior_path_side_shift_module to new test manager
- adapt behavior_path_static_obstacle_avoidance_module to new test manager
- adapt path_smoother to new test manager
- adapt behavior_velocity_blind_spot_module to new test manager
- adapt behavior_velocity_detection_area_module to new test manager
- adapt behavior_velocity_intersection_module to new test manager
- adapt behavior_velocity_no_stopping_area_module to new test manager
- adapt behavior_velocity_run_out_module to new test manager
- adapt behavior_velocity_stop_line_module to new test manager
- adapt behavior_velocity_traffic_light_module to new test manager
- adapt behavior_velocity_virtual_traffic_light_module to new test manager
- adapt behavior_velocity_walkway_module to new test manager
- adapt motion_velocity_planner_node_universe to new test manager
- include necessary headers
* Odometries -> Odometry ---------Co-authored-by: Takayuki Murooka <<takayuki5168@gmail.com>>
- Contributors: Fumiya Watanabe, Mitsuhiro Sakamoto, Ryohsuke Mitsudome, 心刚
0.41.2 (2025-02-19)
- chore: bump version to 0.41.1 (#10088)
- Contributors: Ryohsuke Mitsudome
0.41.1 (2025-02-10)
0.41.0 (2025-01-29)
- Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base
- docs(crosswalk): fix file add miss (#10028)
- docs(crosswalk): update ttc vs ttv docs (#10025)
- feat(crosswalk): update judgle time against the stopped objects (#9988)
- chore(crosswalk): port the same direction ignore block (#9983)
- feat(crosswalk): add pass marker (#9952)
- chore(planning): move package directory for planning factor
interface
(#9948)
- chore: add new package for planning factor interface
- chore(surround_obstacle_checker): update include file
- chore(obstacle_stop_planner): update include file
- chore(obstacle_cruise_planner): update include file
- chore(motion_velocity_planner): update include file
- chore(bpp): update include file
- chore(bvp-common): update include file
- chore(blind_spot): update include file
- chore(crosswalk): update include file
- chore(detection_area): update include file
- chore(intersection): update include file
- chore(no_drivable_area): update include file
- chore(no_stopping_area): update include file
- chore(occlusion_spot): update include file
- chore(run_out): update include file
- chore(speed_bump): update include file
- chore(stop_line): update include file
- chore(template_module): update include file
- chore(traffic_light): update include file
- chore(vtl): update include file
- chore(walkway): update include file
* chore(motion_utils): remove factor interface ---------
- feat(planning_factor)!: remove velocity_factor, steering_factor and introduce planning_factor (#9927) Co-authored-by: Satoshi OTA <<44889564+satoshi-ota@users.noreply.github.com>> Co-authored-by: Ryohsuke Mitsudome <<43976834+mitsudome-r@users.noreply.github.com>> Co-authored-by: satoshi-ota <<satoshi.ota928@gmail.com>>
- fix: remove unnecessary parameters (#9935)
- feat(behavior_velocity_modules): add node test
(#9790)
- feat(behavior_velocity_crosswalk): add node test
- fix
- feat(behavior_velocity_xxx_module): add node test
- fix
- fix
- fix
- fix
* change directory tests -> test ---------
- refactor(behavior_velocity_planner_common): add
behavior_velocity_rtc_interface and move RTC-related
implementation
(#9799)
- split into planer_common and rtc_interface
* Update planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp Co-authored-by: Mamoru Sobue <<mamoru.sobue@tier4.jp>> * Update planning/behavior_velocity_planner/autoware_behavior_velocity_rtc_interface/include/autoware/behavior_velocity_rtc_interface/scene_module_interface_with_rtc.hpp Co-authored-by: Mamoru Sobue <<mamoru.sobue@tier4.jp>> * fix ——
Co-authored-by: Mamoru Sobue <<mamoru.sobue@tier4.jp>>
- feat(behavior_velocity_planner): use XXXStamped in
autoware_internal_debug_msgs
(#9744)
- feat(behavior_velocity_planner): use XXXStamped in autoware_internal_debug_msgs
* fix
- feat(behavior_velocity_planner): remove unnecessary tier4_api_msgs (#9692)
- Contributors: Fumiya Watanabe, Mamoru Sobue, Satoshi OTA, Takayuki Murooka, Yuki TAKAGI
0.40.0 (2024-12-12)
- Merge branch 'main' into release-0.40.0
- Revert "chore(package.xml): bump version to 0.39.0 (#9587)" This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5.
- fix: fix ticket links in CHANGELOG.rst (#9588)
- chore(package.xml): bump version to 0.39.0
(#9587)
- chore(package.xml): bump version to 0.39.0
- fix: fix ticket links in CHANGELOG.rst
* fix: remove unnecessary diff ---------Co-authored-by: Yutaka Kondo <<yutaka.kondo@youtalk.jp>>
- fix: fix ticket links in CHANGELOG.rst (#9588)
- fix(cpplint): include what you use - planning (#9570)
- feat(behavior_velocity_planner)!: remove stop_reason (#9452)
- 0.39.0
- update changelog
- Merge commit '6a1ddbd08bd' into release-0.39.0
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- chore(crosswalk)!: delete wide crosswalk corresponding function (#9329)
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- chore(package.xml): bump version to 0.38.0
(#9266)
(#9284)
- unify package.xml version to 0.37.0
- remove system_monitor/CHANGELOG.rst
- add changelog
* 0.38.0
- fix(crosswalk): don't use vehicle stop checker to remove unnecessary callback (#9234)
- test(crosswalk): add unit test (#9228)
- Contributors: Esteve Fernandez, Fumiya Watanabe, M. Fatih Cırıt, Mamoru Sobue, Ryohsuke Mitsudome, Satoshi OTA, Yuki TAKAGI, Yutaka Kondo
0.39.0 (2024-11-25)
- Merge commit '6a1ddbd08bd' into release-0.39.0
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- chore(package.xml): bump version to 0.38.0
(#9266)
(#9284)
- unify package.xml version to 0.37.0
- remove system_monitor/CHANGELOG.rst
- add changelog
* 0.38.0
- fix(crosswalk): don't use vehicle stop checker to remove unnecessary callback (#9234)
- test(crosswalk): add unit test (#9228)
- Contributors: Esteve Fernandez, Satoshi OTA, Yuki TAKAGI, Yutaka Kondo
0.38.0 (2024-11-08)
- unify package.xml version to 0.37.0
- refactor(autoware_grid_map_utils): prefix folder structure with autoware/ (#9170)
- fix(crosswalk): fix occlusion detection range calculation and add debug markers (#9121)
- fix(crosswalk): fix passing direction calclation for the objects (#9071)
- fix(crosswalk): change exceptional handling (#8956)
- refactor(autoware_interpolation): prefix package and namespace with autoware (#8088) Co-authored-by: kosuke55 <<kosuke.tnp@gmail.com>>
- feat(crosswalk)!: update stop position caluculation (#8853)
- feat(crosswalk): suppress restart when the ego is close to the next
stop point
(#8817)
- feat(crosswalk): suppress restart when the ego is close to the next stop point
- update
* add comment ---------
- fix(behavior_velocity_planner): align the parameters with launcher (#8791) parameters in behavior_velocity_planner aligned
- fix(autoware_behavior_velocity_crosswalk_module): fix unusedFunction (#8665) fix:unusedFunction
- fix(crosswalk): fix findEgoPassageDirectionAlongPath finding front
and back point logic
(#8459)
- fix(crosswalk): fix findEgoPassageDirectionAlongPath finding front and back point logic
* define ego_crosswalk_passage_direction later ---------
- fix(behavior_velocity_planner): fix cppcheck warnings of virtualCallInConstructor (#8376) Co-authored-by: Ryuta Kambe <<ryuta.kambe@tier4.jp>>
- fix(autoware_behavior_velocity_crosswalk_module): fix
passedByValue
(#8210)
- fix:passedByValue
* fix:passedByValue ---------
- refactor(crosswalk): clean up the structure and create a brief
flowchart
(#7868)
- refactor(crosswalk): clean up the structure and create a brief flowchart
- update
- fix
* static stop pose -> default stop pose ---------
- fix(autoware_behavior_velocity_crosswalk_module): fix
shadowVariable
(#7974)
- fix:shadowVariable
* fix:shadowVariable ---------
- feat: add [autoware_]{.title-ref} prefix to [lanelet2_extension]{.title-ref} (#7640)
- refactor(universe_utils/motion_utils)!: add autoware namespace (#7594)
- refactor(motion_utils)!: add autoware prefix and include dir (#7539) refactor(motion_utils): add autoware prefix and include dir
- feat(autoware_universe_utils)!: rename from tier4_autoware_utils (#7538) Co-authored-by: kosuke55 <<kosuke.tnp@gmail.com>>
- chore(behavior_velocity_planner): move packages (#7526)
- Contributors: Esteve Fernandez, Fumiya Watanabe, Kosuke Takeuchi, Maxime CLEMENT, Mehmet Dogru, Takayuki Murooka, Yuki TAKAGI, Yutaka Kondo, Zhe Shen, kobayu858, taisa1
0.26.0 (2024-04-03)
Wiki Tutorials
Package Dependencies
System Dependencies
Name |
---|
eigen |
libboost-dev |