Skip to content

Commit

Permalink
Merge pull request #695 from tier4/sync-awf-upstream
Browse files Browse the repository at this point in the history
chore: sync tier4/autoware_launch:awf-latest
  • Loading branch information
tier4-autoware-public-bot[bot] authored Nov 28, 2024
2 parents 3e6f51d + 67ca494 commit ca6bc2d
Show file tree
Hide file tree
Showing 28 changed files with 2,514 additions and 96 deletions.
File renamed without changes.
2,315 changes: 2,315 additions & 0 deletions autoware_launch/CHANGELOG.rst

Large diffs are not rendered by default.

Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,13 @@
# Ego path calculation
use_predicted_trajectory: true
use_imu_path: true
limit_imu_path_lat_dev: false
limit_imu_path_length: true
use_pointcloud_data: true
use_predicted_object_data: false
use_object_velocity_calculation: true
check_autoware_state: true
imu_path_lat_dev_threshold: 1.75
min_generated_imu_path_length: 0.5
max_generated_imu_path_length: 10.0
imu_prediction_time_horizon: 1.5
Expand Down Expand Up @@ -37,7 +40,7 @@
maximum_cluster_size: 10000

# RSS distance collision check
longitudinal_offset: 1.0
longitudinal_offset_margin: 1.0
t_response: 1.0
a_ego_min: -3.0
a_obj_min: -1.0
Expand Down
39 changes: 39 additions & 0 deletions autoware_launch/config/control/preset/default_preset.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
launch:
# controller
- arg:
name: trajectory_follower_mode
default: trajectory_follower_node
# option: trajectory_follower_node
# smart_mpc_trajectory_follower
# none

# external_cmd selector/converter
- arg:
name: launch_external_cmd_selector
default: "true"
- arg:
name: launch_external_cmd_converter
default: "true"

# optional control checkers
- arg:
name: launch_lane_departure_checker
default: "true"
- arg:
name: launch_control_validator
default: "true"
- arg:
name: launch_autonomous_emergency_braking
default: "true"
- arg:
name: launch_collision_detector
default: "true"
- arg:
name: launch_obstacle_collision_checker
default: "false"
- arg:
name: launch_predicted_path_checker
default: "false"
- arg:
name: launch_control_evaluator
default: "true"
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
launch:
# controller
- arg:
name: trajectory_follower_mode
default: none
# option: trajectory_follower_node
# smart_mpc_trajectory_follower
# none

# external_cmd selector/converter
- arg:
name: launch_external_cmd_selector
default: "false"
- arg:
name: launch_external_cmd_converter
default: "false"

# optional control checkers
- arg:
name: launch_lane_departure_checker
default: "false"
- arg:
name: launch_control_validator
default: "true"
- arg:
name: launch_autonomous_emergency_braking
default: "false"
- arg:
name: launch_collision_detector
default: "false"
- arg:
name: launch_obstacle_collision_checker
default: "false"
- arg:
name: launch_predicted_path_checker
default: "false"
- arg:
name: launch_control_evaluator
default: "false"
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
publish_rate: 10.0
world_frame_id: map
enable_delay_compensation: true
consider_odometry_uncertainty: false

# debug parameters
publish_processing_time: true
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
use_virtual_ground_point: True
split_height_distance: 0.2
non_ground_height_threshold: 0.20
grid_size_m: 0.1
grid_size_m: 0.5
grid_mode_switch_radius: 20.0
gnd_grid_buffer_size: 4
detection_range_z_max: 2.5
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -139,13 +139,13 @@
min_velocity: 1.0
min_acceleration: 1.0
max_velocity: 1.0
time_horizon_for_front_object: 10.0
time_horizon_for_rear_object: 10.0
time_horizon_for_front_object: 5.0
time_horizon_for_rear_object: 5.0
time_resolution: 0.5
delay_until_departure: 1.0
# For target object filtering
target_filtering:
safety_check_time_horizon: 10.0
safety_check_time_horizon: 5.0
safety_check_time_resolution: 1.0
# detection range
object_check_forward_distance: 100.0
Expand Down Expand Up @@ -179,7 +179,7 @@
# safety check configuration
enable_safety_check: true
method: "integral_predicted_polygon"
keep_unsafe_time: 3.0
keep_unsafe_time: 0.5
# collision check parameters
publish_debug_marker: false
rss_params:
Expand All @@ -192,7 +192,7 @@
forward_margin: 1.0
backward_margin: 1.0
lat_margin: 1.0
time_horizon: 10.0
time_horizon: 5.0
# hysteresis factor to expand/shrink polygon with the value
hysteresis_factor_expand_rate: 1.0
collision_check_yaw_diff_threshold: 3.1416
Expand Down
Original file line number Diff line number Diff line change
@@ -1,42 +1,38 @@
/**:
ros__parameters:
lane_change:
backward_lane_length: 200.0 #[m]
prepare_duration: 4.0 # [s]

backward_lane_length: 200.0
backward_length_buffer_for_end_of_lane: 3.0 # [m]
backward_length_buffer_for_blocking_object: 3.0 # [m]
backward_length_from_intersection: 5.0 # [m]

lane_changing_lateral_jerk: 0.5 # [m/s3]

minimum_lane_changing_velocity: 2.78 # [m/s]
prediction_time_resolution: 0.5 # [s]
longitudinal_acceleration_sampling_num: 5
lateral_acceleration_sampling_num: 3

# side walk parked vehicle
object_check_min_road_shoulder_width: 0.5 # [m]
object_shiftable_ratio_threshold: 0.6

# turn signal
min_length_for_turn_signal_activation: 10.0 # [m]
length_ratio_for_turn_signal_deactivation: 0.8 # ratio (desired end position)

# longitudinal acceleration
min_longitudinal_acc: -1.0
max_longitudinal_acc: 1.0

skip_process:
longitudinal_distance_diff_threshold:
prepare: 1.0
lane_changing: 1.0
# trajectory generation
trajectory:
prepare_duration: 4.0
lateral_jerk: 0.5
min_longitudinal_acc: -1.0
max_longitudinal_acc: 1.0
th_prepare_length_diff: 1.0
th_lane_changing_length_diff: 1.0
min_lane_changing_velocity: 2.78
lon_acc_sampling_num: 5
lat_acc_sampling_num: 3

# delay lane change
delay_lane_change:
enable: true
check_only_parked_vehicle: false
min_road_shoulder_width: 0.5 # [m]
th_parked_vehicle_shift_ratio: 0.6

# safety check
safety_check:
allow_loose_check_for_cancel: true
enable_target_lane_bound_check: true
collision_check_yaw_diff_threshold: 3.1416
stopped_object_velocity_threshold: 1.0 # [m/s]
execution:
expected_front_deceleration: -1.0
expected_rear_deceleration: -1.0
Expand Down Expand Up @@ -93,14 +89,16 @@
pedestrian: true

# collision check
enable_collision_check_for_prepare_phase:
general_lanes: false
intersection: true
turns: true
stopped_object_velocity_threshold: 1.0 # [m/s]
check_objects_on_current_lanes: false
check_objects_on_other_lanes: false
use_all_predicted_path: false
collision_check:
enable_for_prepare_phase:
general_lanes: false
intersection: true
turns: true
prediction_time_resolution: 0.5
yaw_diff_threshold: 3.1416
check_current_lanes: false
check_other_lanes: false
use_all_predicted_paths: false

# lane change regulations
regulation:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,3 @@
backward_path_length: 5.0
behavior_output_path_interval: 1.0
stop_line_extend_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,7 @@
/**:
ros__parameters:
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
Expand Up @@ -13,8 +13,6 @@

# For the Lanelet2 map with no explicit stop lines
stop_distance_from_crosswalk: 3.5 # [m] make stop line away from crosswalk
# For the case where the crosswalk width is very wide
far_object_threshold: 10.0 # [m] 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 stop position is determined according to the object position.
stop_distance_from_object_preferred: 3.0 # [m]
stop_distance_from_object_limit: 3.0 # [m]
Expand Down Expand Up @@ -79,7 +77,7 @@

# param for occlusions
occlusion:
enable: true # if true, ego will slowdown around crosswalks that are occluded
enable: false # if true, ego will slowdown around crosswalks that are occluded
occluded_object_velocity: 2.0 # [m/s] assumed velocity of objects that may come out of the occluded space
slow_down_velocity: 1.0 # [m/s]
time_buffer: 0.5 # [s] consecutive time with/without an occlusion to add/remove the slowdown
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
th_stopped_velocity_mps: 0.01
th_course_out_distance_m: 1.0
th_obstacle_time_sec: 1.0
vehicle_shape_margin_m: 0.5
vehicle_shape_margin_m: 0.4
replan_when_obstacle_found: true
replan_when_course_out: true

Expand Down

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -14,4 +14,23 @@
/**:
ros__parameters:
required_diags:
dummy_diag_empty: default
# map
## /autoware/map/topic_rate_check/pointcloud_map
"topic_state_monitor_pointcloud_map: map_topic_status": default

# localization
## /autoware/localization/scan_matching_status
"ndt_scan_matcher: scan_matching_status": default

## /autoware/localization/accuracy
"localization_error_monitor: ellipse_error_status": default

## /autoware/localization/sensor_fusion_status
"localization: ekf_localizer": default

## /autoware/localization/topic_rate_check/pose_twist_fusion
"topic_state_monitor_pose_twist_fusion_filter_pose: localization_topic_status": default

# perception
## /autoware/perception/topic_rate_check/pointcloud
"topic_state_monitor_obstacle_segmentation_pointcloud: perception_topic_status": default
Original file line number Diff line number Diff line change
Expand Up @@ -2,13 +2,17 @@
ros__parameters:
update_rate: 10.0
processing_time_topic_name_list:
- /control/control_evaluator/debug/processing_time_ms
- /control/control_validator/debug/processing_time_ms
- /control/trajectory_follower/controller_node_exe/lateral/debug/processing_time_ms
- /control/trajectory_follower/controller_node_exe/longitudinal/debug/processing_time_ms
- /control/trajectory_follower/lane_departure_checker_node/debug/processing_time_ms
- /control/vehicle_cmd_gate/debug/processing_time_ms
- /perception/object_recognition/prediction/map_based_prediction/debug/processing_time_ms
- /perception/object_recognition/tracking/multi_object_tracker/debug/processing_time_ms
- /planning/mission_planning/mission_planner/debug/processing_time_ms
- /planning/mission_planning/route_selector/debug/processing_time_ms
- /planning/planning_evaluator/debug/processing_time_ms
- /planning/planning_validator/debug/processing_time_ms
- /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/avoidance_by_lane_change/processing_time_ms
- /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner/debug/dynamic_obstacle_avoidance/processing_time_ms
Expand Down Expand Up @@ -37,6 +41,7 @@
- /planning/scenario_planning/lane_driving/motion_planning/path_optimizer/debug/processing_time_ms
- /planning/scenario_planning/lane_driving/motion_planning/surround_obstacle_checker/debug/processing_time_ms
- /planning/scenario_planning/parking/costmap_generator/debug/processing_time_ms
- /planning/scenario_planning/parking/freespace_planner/debug/processing_time_ms
- /planning/scenario_planning/scenario_selector/debug/processing_time_ms
- /planning/scenario_planning/velocity_smoother/debug/processing_time_ms
- /simulation/shape_estimation/debug/processing_time_ms
Loading

0 comments on commit ca6bc2d

Please sign in to comment.