Skip to content

Commit

Permalink
Merge pull request #326 from tier4/beta-to-tier4-main-sync
Browse files Browse the repository at this point in the history
chore: sync beta branch beta/v0.23.0 with tier4/main
  • Loading branch information
tier4-autoware-public-bot[bot] authored Feb 26, 2024
2 parents d88b9d1 + 58afe92 commit 544e0ba
Show file tree
Hide file tree
Showing 38 changed files with 147 additions and 53 deletions.
Original file line number Diff line number Diff line change
@@ -1,8 +1,6 @@
/**:
ros__parameters:

publish_diag: false # if true, diagnostic msg is published

# If the number of consecutive invalid predicted_path exceeds this threshold, the Diag will be set to ERROR.
# (For example, threshold = 1 means, even if the predicted_path is invalid, Diag will not be ERROR if
# the next predicted_path is valid.)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
curvature_smoothing_num_ref_steer: 15 # point-to-point index distance used in curvature calculation (for steer command reference): curvature is calculated from three points p(i-num), p(i), p(i+num)

# -- trajectory extending --
extend_trajectory_for_end_yaw_control: true # flag of trajectory extending for terminal yaw control
extend_trajectory_for_end_yaw_control: false # flag of trajectory extending for terminal yaw control

# -- mpc optimization --
qp_solver_type: "osqp" # optimization solver option (unconstraint_fast or osqp)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,8 +69,9 @@
max_jerk: 2.0
min_jerk: -5.0

# pitch
use_trajectory_for_pitch_calculation: false
# slope compensation
lpf_pitch_gain: 0.95
slope_source: "raw_pitch" # raw_pitch, trajectory_pitch or trajectory_adaptive
adaptive_trajectory_velocity_th: 1.0
max_pitch_rad: 0.1
min_pitch_rad: -0.1
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
update_rate: 10.0
system_emergency_heartbeat_timeout: 0.5
use_emergency_handling: false
check_external_emergency_heartbeat: false
check_external_emergency_heartbeat: $(var check_external_emergency_heartbeat)
use_start_request: false
enable_cmd_limit_filter: true
filter_activated_count_threshold: 5
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
/**:
ros__parameters:
# marker_size
marker_size: 0.6

# target_tag_ids
target_tag_ids: ['0','1','2','3','4','5','6']

# base_covariance
# This value is dynamically scaled according to the distance at which AR tags are detected.
base_covariance: [0.2, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.2, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.2, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.02, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.02, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.02]

# Detect AR-Tags within this range and publish the pose of ego vehicle
distance_threshold: 13.0 # [m]

# consider_orientation
consider_orientation: false

# Detector parameters
# See https://github.com/pal-robotics/aruco_ros/blob/7787a6794d30c248bc546d1582e65dd47bc40c12/aruco/include/aruco/markerdetector.h#L106-L126
detection_mode: "DM_NORMAL" # select from [DM_NORMAL, DM_FAST, DM_VIDEO_FAST]
min_marker_size: 0.02

# Parameters for comparison with EKF Pose
# If the difference between the EKF pose and the current pose is within the range of values set below, the current pose is published.
# [How to determine the value]
# * ekf_time_tolerance: Since it is abnormal if the data comes too old from EKF, the tentative tolerance value is set at 5 seconds.
# This value is assumed to be unaffected even if it is increased or decreased by some amount.
# * ekf_position_tolerance: Since it is possible that multiple AR tags with the same ID could be placed, the tolerance should be as small as possible.
# And if the vehicle is running only on odometry in a section without AR tags,
# it is possible that self-position estimation could be off by a few meters.
# it should be fixed by AR tag detection, so tolerance should not be smaller than 10 meters.
# Therefore, the tolerance is set at 10 meters.
ekf_time_tolerance: 5.0 # [s]
ekf_position_tolerance: 10.0 # [m]
1 change: 1 addition & 0 deletions autoware_launch/config/map/lanelet2_map_loader.param.yaml
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
/**:
ros__parameters:
center_line_resolution: 5.0 # [m]
lanelet2_map_path: $(var lanelet2_map_path) # The lanelet2 map path
2 changes: 2 additions & 0 deletions autoware_launch/config/map/pointcloud_map_loader.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -7,3 +7,5 @@

# only used when downsample_whole_load enabled
leaf_size: 3.0 # downsample leaf size [m]
pcd_paths_or_directory: [$(var pointcloud_map_path)] # Path to the pointcloud map file or directory
pcd_metadata_path: $(var pointcloud_map_metadata_path) # Path to pointcloud metadata file
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@
iou_nms_threshold: 0.1
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]
score_threshold: 0.35
build_only: false # shutdown node after TensorRT engine file is built
has_twist: false
trt_precision: fp16
densification_num_past_frames: 1
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
iou_nms_target_class_names: ["CAR"]
iou_nms_search_distance_2d: 10.0
iou_nms_threshold: 0.1
score_threshold: 0.4
score_threshold: 0.35
omp_params:
# omp params
num_threads: 1
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,12 @@
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
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 Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,3 +24,6 @@
max_distance_from_lane: 5.0 # [m]
max_angle_diff_from_lane: 0.785398 # [rad] (45 deg)
max_lateral_velocity: 7.0 # [m/s]

# tracking model parameters
tracking_config_directory: $(find-pkg-share autoware_launch)/config/perception/object_recognition/tracking/radar_object_tracker/tracking/
Original file line number Diff line number Diff line change
Expand Up @@ -3,3 +3,4 @@
external_time_tolerance: 5.0
perception_time_tolerance: 1.0
external_priority: false
enable_signal_matching: false
6 changes: 3 additions & 3 deletions autoware_launch/config/planning/preset/default_preset.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ launch:
default: "true"
- arg:
name: launch_dynamic_avoidance_module
default: "false"
default: "true"
- arg:
name: launch_sampling_planner_module
default: "false" # Warning, experimental module, use only in simulations
Expand Down Expand Up @@ -100,7 +100,7 @@ launch:

- arg:
name: motion_stop_planner_type
default: obstacle_stop_planner
default: obstacle_cruise_planner
# option: obstacle_stop_planner
# obstacle_cruise_planner
# none
Expand All @@ -115,7 +115,7 @@ launch:

- arg:
name: launch_surround_obstacle_checker
default: "false"
default: "true"

# parking modules
- arg:
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
/**:
ros__parameters:
max_vel: 11.1 # max velocity limit [m/s]

# constraints param for normal driving
normal:
min_acc: -1.0 # min deceleration [m/ss]
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
/**:
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
Expand All @@ -26,7 +25,7 @@
# 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_acceleration: 0.5 # 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]

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,3 +26,14 @@
steering_rate: 10.0
velocity_deviation: 100.0
distance_deviation: 100.0
longitudinal_distance_deviation: 1.0

parameters:
# The required trajectory length is calculated as the distance needed
# to stop from the current speed at this deceleration.
forward_trajectory_length_acceleration: -3.0

# An error is raised if the required trajectory length is less than this distance.
# Setting it to 0 means an error will occur if even slightly exceeding the end of the path,
# therefore, a certain margin is necessary.
forward_trajectory_length_margin: 2.0
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,7 @@
object_check_return_pose_distance: 20.0 # [m]
# filtering parking objects
threshold_distance_object_is_on_center: 1.0 # [m]
object_check_shiftable_ratio: 0.6 # [-]
object_check_shiftable_ratio: 0.8 # [-]
object_check_min_road_shoulder_width: 0.5 # [m]
# lost object compensation
object_last_seen_threshold: 2.0
Expand Down Expand Up @@ -187,6 +187,7 @@
time_horizon_for_rear_object: 10.0 # [s]
delay_until_departure: 0.0 # [s]
# rss parameters
extended_polygon_policy: "along_path" # [-] select "rectangle" or "along_path"
expected_front_deceleration: -1.0 # [m/ss]
expected_rear_deceleration: -1.0 # [m/ss]
rear_vehicle_reaction_time: 2.0 # [s]
Expand All @@ -206,7 +207,7 @@
hard_road_shoulder_margin: 0.3 # [m]
max_right_shift_length: 5.0
max_left_shift_length: 5.0
max_deviation_from_lane: 0.5 # [m]
max_deviation_from_lane: 0.2 # [m]
# avoidance distance parameters
longitudinal:
min_prepare_time: 1.0 # [s]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,10 +35,14 @@
# object recognition
object_recognition:
use_object_recognition: true
object_recognition_collision_check_margin: 0.6 # this should be larger than `surround_check_distance` of surround_obstacle_checker
collision_check_soft_margins: [2.0, 1.5, 1.0]
collision_check_hard_margins: [0.6] # this should be larger than `surround_check_distance` of surround_obstacle_checker
object_recognition_collision_check_max_extra_stopping_margin: 1.0
th_moving_object_velocity: 1.0
detection_bound_offset: 15.0
outer_road_detection_offset: 1.0
inner_road_detection_offset: 0.0


# pull over
pull_over:
Expand Down Expand Up @@ -128,7 +132,7 @@
delay_until_departure: 1.0
# For target object filtering
target_filtering:
safety_check_time_horizon: 5.0
safety_check_time_horizon: 10.0
safety_check_time_resolution: 1.0
# detection range
object_check_forward_distance: 100.0
Expand Down Expand Up @@ -164,7 +168,6 @@
method: "integral_predicted_polygon"
keep_unsafe_time: 3.0
# collision check parameters
check_all_predicted_path: true
publish_debug_marker: false
rss_params:
rear_vehicle_reaction_time: 2.0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@
th_stopped_velocity: 0.01
th_stopped_time: 1.0
collision_check_margins: [2.0, 1.0, 0.5, 0.1]
collision_check_distance_from_end: -10.0
collision_check_margin_from_front_object: 5.0
th_moving_object_velocity: 1.0
th_distance_to_middle_of_the_road: 0.5
Expand Down Expand Up @@ -39,6 +38,7 @@
backward_path_update_duration: 3.0
ignore_distance_from_lane_end: 15.0
# turns signal
prepare_time_before_start: 0.0
th_turn_signal_on_lateral_offset: 1.0
intersection_search_length: 30.0
length_ratio_for_turn_signal_deactivation_near_intersection: 0.5
Expand Down Expand Up @@ -93,7 +93,7 @@
delay_until_departure: 1.0
# For target object filtering
target_filtering:
safety_check_time_horizon: 5.0
safety_check_time_horizon: 10.0
safety_check_time_resolution: 1.0
# detection range
object_check_forward_distance: 10.0
Expand Down Expand Up @@ -127,7 +127,6 @@
# safety check configuration
enable_safety_check: true
# collision check parameters
check_all_predicted_path: true
publish_debug_marker: false
rss_params:
rear_vehicle_reaction_time: 2.0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
use_pass_judge_line: true
stop_line_margin: 1.0 # [m]
backward_length: 50.0 # [m]
ignore_width_from_center_line: 0.7 # [m]
ignore_width_from_center_line: 0.0 # [m]
max_future_movement_time: 10.0 # [second]
threshold_yaw_diff: 0.523 # [rad]
adjacent_extend_width: 1.5 # [m]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
ego_pass_first_margin_y: [3.0] # [[s]] 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: 0.5 # [s] additional time margin for ego pass first situation to suppress chattering
ego_pass_later_margin_x: [0.0] # [[s]] 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: [10.0] # [[s]] 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_margin_y: [13.0] # [[s]] 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: 0.5 # [s] additional time margin for object pass first situation to suppress chattering

no_stop_decision: # parameters to determine if it is safe to attempt stopping before the crosswalk
Expand All @@ -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
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,14 @@
enable_pass_judge_before_default_stopline: false

stuck_vehicle:
target_type:
car: true
bus: true
truck: true
trailer: true
motorcycle: false
bicycle: false
unknown: false
turn_direction:
left: true
right: true
Expand All @@ -27,6 +35,14 @@
disable_against_private_lane: true

yield_stuck:
target_type:
car: true
bus: true
truck: true
trailer: true
motorcycle: false
bicycle: false
unknown: false
turn_direction:
left: true
right: true
Expand All @@ -37,6 +53,14 @@
consider_wrong_direction_vehicle: false
collision_detection_hold_time: 0.5
min_predicted_path_confidence: 0.05
target_type:
car: true
bus: true
truck: true
trailer: true
motorcycle: true
bicycle: true
unknown: false
velocity_profile:
use_upstream: true
minimum_upstream_velocity: 0.01
Expand All @@ -56,7 +80,9 @@
duration: 3.0
object_dist_to_stopline: 10.0
ignore_on_amber_traffic_light:
object_expected_deceleration: 2.0
object_expected_deceleration:
car: 2.0
bike: 5.0
ignore_on_red_traffic_light:
object_margin_to_path: 2.0
avoid_collision_by_acceleration:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
option:
enable_skip_optimization: false # skip elastic band and model predictive trajectory
enable_reset_prev_optimization: false # If true, optimization has no fix constraint to the previous result.
enable_outside_drivable_area_stop: true # stop if the ego's trajectory footprint is outside the drivable area
enable_outside_drivable_area_stop: false # stop if the ego's trajectory footprint is outside the drivable area
use_footprint_polygon_for_outside_drivable_area_check: false # If false, only the footprint's corner points are considered.

debug:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
idling_time: 2.0 # idling time to detect front vehicle starting deceleration [s]
min_ego_accel_for_rss: -1.0 # ego's acceleration to calculate RSS distance [m/ss]
min_object_accel_for_rss: -1.0 # front obstacle's acceleration to calculate RSS distance [m/ss]
safe_distance_margin : 6.0 # This is also used as a stop margin [m]
safe_distance_margin : 5.0 # This is also used as a stop margin [m]
terminal_safe_distance_margin : 3.0 # Stop margin at the goal. This value cannot exceed safe distance margin. [m]
hold_stop_velocity_threshold: 0.01 # The maximum ego velocity to hold stopping [m/s]
hold_stop_distance_threshold: 0.3 # The ego keeps stopping if the distance to stop changes within the threshold [m]
Expand Down
Loading

0 comments on commit 544e0ba

Please sign in to comment.