Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(map based prediction, crosswalk)!: transplantation of pedestrians' behavior prediction against green signal #860

Merged
Show file tree
Hide file tree
Changes from 5 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,13 @@
min_acceleration_before_curve: -2.0 # [m/ss] min acceleration a vehicle might take to decelerate before a curve
use_vehicle_acceleration: false # whether to consider current vehicle acceleration when predicting paths or not
speed_limit_multiplier: 1.5 # When using vehicle acceleration. Set vehicle's maximum predicted speed as the legal speed limit in that lanelet times this value
acceleration_exponential_half_life: 2.5 # [s] When using vehicle acceleration. The decaying acceleration model considers that the current vehicle acceleration will be halved after this many seconds
use_crosswalk_signal: true
acceleration_exponential_half_life: 2.5 # [s] When using vehicle acceleration. The decaying acceleration model considers that the current vehicle acceleration will be halved after this many seconds
crosswalk_with_signal:
use_crosswalk_signal: true
threshold_velocity_assumed_as_stopping: 0.25 # [m/s] velocity threshold for the module to judge whether the objects is stopped
# If the pedestrian does not move for X seconds against green signal, the module judge that the pedestrian has no intention to walk.
distance_set_for_no_intention_to_walk: [1.0, 5.0] # [m] ascending order, keys of map
timeout_set_for_no_intention_to_walk: [1.0, 0.0] # [s] values of map
# parameter for shoulder lane prediction
prediction_time_horizon_rate_for_validate_shoulder_lane_length: 0.8

Expand All @@ -36,6 +41,6 @@
diff_dist_threshold_to_left_bound: 0.29 #[m]
diff_dist_threshold_to_right_bound: -0.29 #[m]
num_continuous_state_transition: 3
consider_only_routable_neighbours: false

Check warning on line 44 in autoware_launch/config/perception/object_recognition/prediction/map_based_prediction.param.yaml

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (routable)

reference_path_resolution: 0.5 #[m]
Original file line number Diff line number Diff line change
Expand Up @@ -53,11 +53,10 @@
stop_object_velocity_threshold: 0.25 # [m/s] velocity threshold for the module to judge whether the objects is stopped (0.25 m/s = 0.9 kmph)
min_object_velocity: 1.39 # [m/s] minimum object velocity (compare the estimated velocity by perception module with this parameter and adopt the larger one to calculate TTV. 1.39 m/s = 5.0 kmph)
## param for yielding
disable_stop_for_yield_cancel: true # for the crosswalks with traffic signal
disable_yield_for_new_stopped_object: true # for the crosswalks with traffic signal
# If the pedestrian does not move for X seconds after the ego has stopped in front the crosswalk, the module judge that the pedestrian has no intention to walk and allows the ego to proceed.
distance_map_for_no_intention_to_walk: [1.0, 5.0] # [m] ascending order
timeout_map_for_no_intention_to_walk: [1.0, 0.0] # [s]
distance_set_for_no_intention_to_walk: [1.0, 5.0] # [m] ascending order
timeout_set_for_no_intention_to_walk: [1.0, 0.0] # [s]
timeout_ego_stop_for_yield: 1.0 # [s] If the ego maintains the stop for this amount of time, then the ego proceeds, assuming it has stopped long time enough.

# param for target object filtering
Expand Down
Loading