Skip to content

Commit

Permalink
feat(autoware_launch): move config from autoware.universe for planning (
Browse files Browse the repository at this point in the history
#133)

* feat(autoware_launch): move config from autoware.universe for planning

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>

* remove unnecessary config

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>

* add rtc

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>

* apply universe param change

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>

Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
  • Loading branch information
takayuki5168 authored Dec 21, 2022
1 parent a4b7ccb commit 55a7a0e
Show file tree
Hide file tree
Showing 37 changed files with 1,208 additions and 3 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
/**:
ros__parameters:
# constraints param for normal driving
normal:
min_acc: -0.5 # min deceleration [m/ss]
max_acc: 1.0 # max acceleration [m/ss]
min_jerk: -0.5 # min jerk [m/sss]
max_jerk: 1.0 # max jerk [m/sss]

# constraints to be observed
limit:
min_acc: -2.5 # min deceleration limit [m/ss]
max_acc: 1.0 # max acceleration limit [m/ss]
min_jerk: -1.5 # min jerk limit [m/sss]
max_jerk: 1.5 # max jerk limit [m/sss]
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
/**:
ros__parameters:
resample:
ds_resample: 0.1
num_resample: 1
delta_yaw_threshold: 0.785

latacc:
enable_constant_velocity_while_turning: false
constant_velocity_dist_threshold: 2.0

forward:
max_acc: 1.0
min_acc: -1.0
max_jerk: 0.3
min_jerk: -0.3
kp: 0.3

backward:
start_jerk: -0.1
min_jerk_mild_stop: -0.3
min_jerk: -1.5
min_acc_mild_stop: -1.0
min_acc: -2.5
span_jerk: -0.01
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
/**:
ros__parameters:
jerk_weight: 0.1 # weight for "smoothness" cost for jerk
over_v_weight: 10000.0 # weight for "over speed limit" cost
over_a_weight: 500.0 # weight for "over accel limit" cost
over_j_weight: 200.0 # weight for "over jerk limit" cost
jerk_filter_ds: 0.1 # resampling ds for jerk filter
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
/**:
ros__parameters:
pseudo_jerk_weight: 100.0 # weight for "smoothness" cost
over_v_weight: 100000.0 # weight for "over speed limit" cost
over_a_weight: 1000.0 # weight for "over accel limit" cost
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
/**:
ros__parameters:
pseudo_jerk_weight: 200.0 # weight for "smoothness" cost
over_v_weight: 100000.0 # weight for "over speed limit" cost
over_a_weight: 5000.0 # weight for "over accel limit" cost
Original file line number Diff line number Diff line change
@@ -0,0 +1,58 @@
/**:
ros__parameters:
# motion state constraints
max_velocity: 20.0 # max velocity limit [m/s]
stop_decel: 0.0 # deceleration at a stop point[m/ss]

# external velocity limit parameter
margin_to_insert_external_velocity_limit: 0.3 # margin distance to insert external velocity limit [m]

# curve parameters
max_lateral_accel: 1.0 # max lateral acceleration limit [m/ss]
min_curve_velocity: 0.5 # min velocity at lateral acceleration limit and steering angle rate limit [m/s]
decel_distance_before_curve: 3.5 # slow speed distance before a curve for lateral acceleration limit
decel_distance_after_curve: 2.0 # slow speed distance after a curve for lateral acceleration limit
min_decel_for_lateral_acc_lim_filter: -2.5 # deceleration limit applied in the lateral acceleration filter to avoid sudden braking [m/ss]

# engage & replan parameters
replan_vel_deviation: 5.53 # velocity deviation to replan initial velocity [m/s]
engage_velocity: 0.25 # engage velocity threshold [m/s] (if the trajectory velocity is higher than this value, use this velocity for engage vehicle speed)
engage_acceleration: 0.1 # engage acceleration [m/ss] (use this acceleration when engagement)
engage_exit_ratio: 0.5 # exit engage sequence to normal velocity planning when the velocity exceeds engage_exit_ratio x engage_velocity.
stop_dist_to_prohibit_engage: 0.5 # if the stop point is in this distance, the speed is set to 0 not to move the vehicle [m]

# stop velocity
stopping_velocity: 2.778 # change target velocity to this value before v=0 point [m/s]
stopping_distance: 0.0 # distance for the stopping_velocity [m]. 0 means the stopping velocity is not applied.

# path extraction parameters
extract_ahead_dist: 200.0 # forward trajectory distance used for planning [m]
extract_behind_dist: 5.0 # backward trajectory distance used for planning [m]
delta_yaw_threshold: 1.0472 # Allowed delta yaw between ego pose and trajectory pose [radian]

# resampling parameters for optimization
max_trajectory_length: 200.0 # max trajectory length for resampling [m]
min_trajectory_length: 150.0 # min trajectory length for resampling [m]
resample_time: 2.0 # resample total time for dense sampling [s]
dense_resample_dt: 0.2 # resample time interval for dense sampling [s]
dense_min_interval_distance: 0.1 # minimum points-interval length for dense sampling [m]
sparse_resample_dt: 0.5 # resample time interval for sparse sampling [s]
sparse_min_interval_distance: 4.0 # minimum points-interval length for sparse sampling [m]

# resampling parameters for post process
post_max_trajectory_length: 300.0 # max trajectory length for resampling [m]
post_min_trajectory_length: 30.0 # min trajectory length for resampling [m]
post_resample_time: 10.0 # resample total time for dense sampling [s]
post_dense_resample_dt: 0.1 # resample time interval for dense sampling [s]
post_dense_min_interval_distance: 0.1 # minimum points-interval length for dense sampling [m]
post_sparse_resample_dt: 0.1 # resample time interval for sparse sampling [s]
post_sparse_min_interval_distance: 1.0 # minimum points-interval length for sparse sampling [m]

# steering angle rate limit parameters
max_steering_angle_rate: 40.0 # maximum steering angle rate [degree/s]
resample_ds: 0.1 # distance between trajectory points [m]
curvature_threshold: 0.02 # if curvature > curvature_threshold, steeringRateLimit is triggered [1/m]
curvature_calculation_distance: 1.0 # distance of points while curvature is calculating [m]

# system
over_stop_velocity_warn_thr: 1.389 # used to check if the optimization exceeds the input velocity on the stop point
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
/**:
ros__parameters:
# ego
ego_nearest_dist_threshold: 3.0 # [m]
ego_nearest_yaw_threshold: 1.046 # [rad] = 60 [deg]
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@
# see AvoidanceParameters description in avoidance_module_data.hpp for description.
/**:
ros__parameters:
avoidance:
resample_interval_for_planning: 0.3
resample_interval_for_output: 4.0
detection_area_right_expand_dist: 0.0
detection_area_left_expand_dist: 1.0

enable_avoidance_over_same_direction: true
enable_avoidance_over_opposite_direction: true
enable_update_path_when_object_is_gone: false

# For target object filtering
threshold_speed_object_is_stopped: 1.0 # [m/s]
threshold_time_object_is_moving: 1.0 # [s]

object_check_forward_distance: 150.0 # [m]
object_check_backward_distance: 2.0 # [m]

threshold_distance_object_is_on_center: 1.0 # [m]

object_check_shiftable_ratio: 0.6 # [-]
object_check_min_road_shoulder_width: 0.5 # [m]

# For lateral margin
object_envelope_buffer: 0.3 # [m]
lateral_collision_margin: 1.0 # [m]
lateral_collision_safety_buffer: 0.7 # [m]

prepare_time: 2.0 # [s]
min_prepare_distance: 1.0 # [m]
min_avoidance_distance: 10.0 # [m]

min_nominal_avoidance_speed: 7.0 # [m/s]
min_sharp_avoidance_speed: 1.0 # [m/s]

road_shoulder_safety_margin: 0.5 # [m]

max_right_shift_length: 5.0
max_left_shift_length: 5.0

nominal_lateral_jerk: 0.2 # [m/s3]
max_lateral_jerk: 1.0 # [m/s3]

# For detection loss compensation
object_last_seen_threshold: 2.0 # [s]

# For prevention of large acceleration while avoidance
min_avoidance_speed_for_acc_prevention: 3.0 # [m/s]
max_avoidance_acceleration: 0.5 # [m/ss]

# bound clipping for objects
enable_bound_clipping: false

# for debug
publish_debug_marker: false
print_debug_info: false

# not enabled yet
longitudinal_collision_margin_min_distance: 0.0 # [m]
longitudinal_collision_margin_time: 0.0


# avoidance is performed for the object type with true
target_object:
car: true
truck: true
bus: true
trailer: true
unknown: false
bicycle: false
motorcycle: false
pedestrian: false

# ---------- advanced parameters ----------
avoidance_execution_lateral_threshold: 0.499
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
/**:
ros__parameters:
backward_path_length: 5.0
forward_path_length: 300.0
backward_length_buffer_for_end_of_lane: 5.0
backward_length_buffer_for_end_of_pull_over: 5.0
backward_length_buffer_for_end_of_pull_out: 5.0
minimum_lane_change_length: 12.0
minimum_pull_over_length: 16.0
refine_goal_search_radius_range: 7.5
turn_signal_intersection_search_distance: 30.0
turn_signal_intersection_angle_threshold_deg: 15.0
turn_signal_minimum_search_distance: 10.0
turn_signal_search_time: 3.0
turn_signal_shift_length_threshold: 0.3
turn_signal_on_swerving: true
path_interval: 2.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
/**:
ros__parameters:
avoidance:
drivable_area_right_bound_offset: 0.0
drivable_area_left_bound_offset: 0.0
lane_change:
drivable_area_right_bound_offset: 0.0
drivable_area_left_bound_offset: 0.0
lane_following:
drivable_area_right_bound_offset: 0.0
drivable_area_left_bound_offset: 0.0
pull_out:
drivable_area_right_bound_offset: 0.0
drivable_area_left_bound_offset: 0.0
pull_over:
drivable_area_right_bound_offset: 0.0
drivable_area_left_bound_offset: 0.0
side_shift:
drivable_area_right_bound_offset: 0.0
drivable_area_left_bound_offset: 0.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
/**:
ros__parameters:
lane_change:
min_stop_distance: 5.0
stop_time: 2.0
hysteresis_buffer_distance: 2.0
lane_change_prepare_duration: 4.0
lane_changing_duration: 8.0
lane_change_finish_judge_buffer: 3.0
minimum_lane_change_velocity: 5.6
prediction_duration: 8.0
prediction_time_resolution: 0.5
static_obstacle_velocity_thresh: 1.5
maximum_deceleration: 1.0
enable_abort_lane_change: true
enable_collision_check_at_prepare_phase: true
use_predicted_path_outside_lanelet: true
use_all_predicted_path: true
enable_blocked_by_obstacle: false
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
/**:
ros__parameters:
lane_following:
lane_change_prepare_duration: 2.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
/**:
ros__parameters:
pull_out:
th_arrived_distance: 1.0
th_stopped_velocity: 0.01
th_stopped_time: 1.0
collision_check_margin: 1.0
pull_out_finish_judge_buffer: 1.0
# shift pull out
enable_shift_pull_out: true
shift_pull_out_velocity: 2.0
pull_out_sampling_num: 4
before_pull_out_straight_distance: 0.0
minimum_shift_pull_out_distance: 20.0
maximum_lateral_jerk: 2.0
minimum_lateral_jerk: 0.5
deceleration_interval: 15.0
# geometric pull out
enable_geometric_pull_out: true
geometric_pull_out_velocity: 1.0
arc_path_interval: 1.0
lane_departure_margin: 0.2
backward_velocity: -1.0
pull_out_max_steer_angle: 0.26 # 15deg
# search start pose backward
enable_back: true
search_priority: "efficient_path" # "efficient_path" or "short_back_distance"
max_back_distance: 15.0
backward_search_resolution: 2.0
backward_path_update_duration: 3.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
/**:
ros__parameters:
pull_over:
request_length: 200.0
th_arrived_distance: 1.0
th_stopped_velocity: 0.01
th_stopped_time: 2.0 # It must be greater than the state_machine's.
pull_over_velocity: 3.0
pull_over_minimum_velocity: 1.38
margin_from_boundary: 0.5
decide_path_distance: 10.0
maximum_deceleration: 1.0
# goal research
enable_goal_research: true
search_priority: "efficient_path" # "efficient_path" or "close_goal"
forward_goal_search_length: 20.0
backward_goal_search_length: 20.0
goal_search_interval: 2.0
longitudinal_margin: 3.0
# occupancy grid map
use_occupancy_grid: true
use_occupancy_grid_for_longitudinal_margin: false
occupancy_grid_collision_check_margin: 0.0
theta_size: 360
obstacle_threshold: 60
# object recognition
use_object_recognition: true
object_recognition_collision_check_margin: 1.0
# shift path
enable_shift_parking: true
pull_over_sampling_num: 4
maximum_lateral_jerk: 2.0
minimum_lateral_jerk: 0.5
deceleration_interval: 15.0
after_pull_over_straight_distance: 5.0
before_pull_over_straight_distance: 5.0
# parallel parking path
enable_arc_forward_parking: true
enable_arc_backward_parking: true
after_forward_parking_straight_distance: 2.0
after_backward_parking_straight_distance: 2.0
forward_parking_velocity: 1.38
backward_parking_velocity: -1.38
forward_parking_lane_departure_margin: 0.0
backward_parking_lane_departure_margin: 0.0
arc_path_interval: 1.0
pull_over_max_steer_angle: 0.35 # 20deg
# hazard on when parked
hazard_on_threshold_distance: 1.0
hazard_on_threshold_velocity: 0.5
# check safety with dynamic objects. Not used now.
pull_over_duration: 2.0
pull_over_prepare_duration: 4.0
min_stop_distance: 5.0
stop_time: 2.0
hysteresis_buffer_distance: 2.0
enable_collision_check_at_prepare_phase: false
use_predicted_path_outside_lanelet: false
use_all_predicted_path: false
# debug
print_debug_info: false
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
/**:
ros__parameters:
side_shift:
min_distance_to_start_shifting: 5.0
time_to_start_shifting: 1.0
shifting_lateral_jerk: 0.2
min_shifting_distance: 5.0
min_shifting_speed: 5.56
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
/**:
ros__parameters:
launch_stop_line: true
launch_crosswalk: true
launch_traffic_light: true
launch_intersection: true
launch_blind_spot: true
launch_detection_area: true
launch_virtual_traffic_light: true
launch_occlusion_spot: true
launch_no_stopping_area: true
launch_run_out: false
forward_path_length: 1000.0
backward_path_length: 5.0
max_accel: -2.8
max_jerk: -5.0
system_delay: 0.5
delay_response_time: 0.5
is_publish_debug_path: false # publish all debug path with lane id in each module
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
/**:
ros__parameters:
blind_spot:
use_pass_judge_line: true
stop_line_margin: 1.0 # [m]
backward_length: 15.0 # [m]
ignore_width_from_center_line: 0.7 # [m]
max_future_movement_time: 10.0 # [second]
Loading

0 comments on commit 55a7a0e

Please sign in to comment.