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

chore: sync awf/autoware_launch #30

Merged
merged 12 commits into from
Apr 7, 2023
Merged
Show file tree
Hide file tree
Changes from all 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
@@ -0,0 +1,6 @@
/**:
ros__parameters:
avoidance_by_lane_change:
execute_object_num: 1
execute_object_longitudinal_margin: 0.0
execute_only_when_lane_change_finish_before_object: true
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
ros__parameters:
verbose: false

groot_zmq_publisher_port: 1666
groot_zmq_server_port: 1667

planning_hz: 10.0
backward_path_length: 5.0
forward_path_length: 300.0
Expand Down
Original file line number Diff line number Diff line change
@@ -1,18 +1,17 @@
/**:
ros__parameters:
lane_change:
lane_change_prepare_duration: 4.0 # [s]
lane_changing_safety_check_duration: 8.0 # [s]
prepare_duration: 4.0 # [s]

minimum_lane_change_prepare_distance: 2.0 # [m]
minimum_lane_change_length: 16.5 # [m]
minimum_prepare_length: 2.0 # [m]
minimum_lane_changing_length: 16.5 # [m]
backward_length_buffer_for_end_of_lane: 3.0 # [m]
lane_change_finish_judge_buffer: 2.0 # [m]

lane_changing_lateral_jerk: 0.5 # [m/s3]
lane_changing_lateral_acc: 0.5 # [m/s2]

minimum_lane_change_velocity: 2.78 # [m/s]
minimum_lane_changing_velocity: 2.78 # [m/s]
prediction_time_resolution: 0.5 # [s]
maximum_deceleration: 1.0 # [m/s2]
lane_change_sampling_num: 3
Expand All @@ -23,6 +22,17 @@
use_predicted_path_outside_lanelet: false
use_all_predicted_path: false

# target object
target_object:
car: true
truck: true
bus: true
trailer: true
unknown: true
bicycle: true
motorcycle: true
pedestrian: true

# abort
enable_cancel_lane_change: true
enable_abort_lane_change: false
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,8 @@

lane_change_right:
enable_module: true
enable_simultaneous_execution: false
priority: 4
enable_simultaneous_execution: true
priority: 5
max_module_size: 1

pull_out:
Expand All @@ -47,6 +47,13 @@

avoidance:
enable_module: true
enable_simultaneous_execution: true
priority: 4
max_module_size: 1

# NOTE: This module is unstable. Deprecated for now.
avoidance_by_lc:
enable_module: false
enable_simultaneous_execution: false
priority: 3
max_module_size: 1
Original file line number Diff line number Diff line change
Expand Up @@ -6,3 +6,4 @@
shifting_lateral_jerk: 0.2
min_shifting_distance: 5.0
min_shifting_speed: 5.56
shift_request_time_limit: 1.0
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
launch_speed_bump: false
forward_path_length: 1000.0
backward_path_length: 5.0
stop_line_extend_length: 5.0
max_accel: -2.8
max_jerk: -5.0
system_delay: 0.5
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,8 @@
blind_spot:
use_pass_judge_line: true
stop_line_margin: 1.0 # [m]
backward_length: 15.0 # [m]
backward_length: 50.0 # [m]
ignore_width_from_center_line: 0.7 # [m]
max_future_movement_time: 10.0 # [second]
threshold_yaw_diff: 0.523 # [rad]
adjacent_extend_width: 1.5 # [m]
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
ego_yield_query_stop_duration: 0.1 # [s] the amount of time which ego should be stopping to query whether it yields or not

# param for input data
external_input_timeout: 1.0
tl_state_timeout: 3.0 # [s] timeout threshold for traffic light signal

# param for target area & object
Expand All @@ -42,3 +43,4 @@
walkway:
stop_duration_sec: 1.0 # [s] stop time at stop position
stop_line_distance: 3.5 # [m] make stop line away from crosswalk when no explicit stop line exists
external_input_timeout: 1.0
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,11 @@
use_stuck_stopline: false # stopline generate before the intersection lanelet when is_stuck
assumed_front_car_decel: 1.0 # [m/ss] the expected deceleration of front car when front car as well as ego are turning
enable_front_car_decel_prediction: false # By default this feature is disabled
stop_overshoot_margin: 0.5 # [m] overshoot margin for stuck, collsion detection
stop_overshoot_margin: 0.5 # [m] overshoot margin for stuck, collision detection
external_input_timeout: 1.0

merge_from_private_road:
stop_duration_sec: 1.0
merge_from_private:
merge_from_private_area:
stop_duration_sec: 1.0
Original file line number Diff line number Diff line change
Expand Up @@ -6,3 +6,6 @@
stop_duration_sec: 1.0
use_initialization_stop_line_state: true
hold_stop_margin_distance: 2.0

debug:
show_stopline_collision_check: false
Original file line number Diff line number Diff line change
Expand Up @@ -6,3 +6,4 @@
dead_line_margin: 1.0
max_yaw_deviation_deg: 90.0
check_timeout_after_stop_line: true
hold_stop_margin_distance: 0.0

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,10 @@
value="$(find-pkg-share autoware_launch)/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/side_shift/side_shift.param.yaml"
/>
<arg name="avoidance_param_path" value="$(find-pkg-share autoware_launch)/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance/avoidance.param.yaml"/>
<arg
name="avoidance_by_lc_param_path"
value="$(find-pkg-share autoware_launch)/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/avoidance_by_lc/avoidance_by_lc.param.yaml"
/>
<arg
name="lane_change_param_path"
value="$(find-pkg-share autoware_launch)/config/planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/lane_change/lane_change.param.yaml"
Expand Down
46 changes: 46 additions & 0 deletions autoware_launch/rviz/autoware.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -1011,6 +1011,29 @@ Visualization Manager:
Constant Color: false
Scale: 0.30000001192092896
Value: true
- Class: rviz_plugins/Path
Color Border Vel Max: 3
Enabled: false
Name: PathReference_AvoidanceByLC
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /planning/path_reference/avoidance_by_lane_change
Value: true
View Path:
Alpha: 0.3
Color: 210; 110; 10
Constant Color: true
Value: true
Width: 2
View Velocity:
Alpha: 0.30000001192092896
Color: 0; 0; 0
Constant Color: false
Scale: 0.30000001192092896
Value: false
- Class: rviz_plugins/Path
Color Border Vel Max: 3
Enabled: false
Expand Down Expand Up @@ -1126,6 +1149,29 @@ Visualization Manager:
Constant Color: false
Scale: 0.30000001192092896
Value: false
- Class: rviz_plugins/Path
Color Border Vel Max: 3
Enabled: true
Name: PathChangeCandidate_AvoidanceByLC
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /planning/path_candidate/avoidance_by_lane_change
Value: true
View Path:
Alpha: 0.30000001192092896
Color: 115; 210; 22
Constant Color: false
Value: true
Width: 2
View Velocity:
Alpha: 0.30000001192092896
Color: 0; 0; 0
Constant Color: false
Scale: 0.30000001192092896
Value: false
- Class: rviz_plugins/Path
Color Border Vel Max: 3
Enabled: true
Expand Down