Skip to content

Commit

Permalink
Merge pull request autowarefoundation#896 from tier4/sync-tier4-upstream
Browse files Browse the repository at this point in the history
chore: sync upstream
  • Loading branch information
tier4-autoware-private-bot[bot] authored Jul 11, 2024
2 parents 8532bba + 819111f commit c52689c
Show file tree
Hide file tree
Showing 13 changed files with 59 additions and 24 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,8 @@
# Ego path calculation
use_predicted_trajectory: true
use_imu_path: false
use_pointcloud_data: true
use_predicted_object_data: false
use_object_velocity_calculation: true
min_generated_path_length: 0.5
imu_prediction_time_horizon: 1.5
Expand All @@ -25,7 +27,8 @@
path_footprint_extra_margin: 4.0

# Point cloud clustering
cluster_tolerance: 0.1 #[m]
cluster_tolerance: 0.15 #[m]
cluster_minimum_height: 0.0
minimum_cluster_size: 10
maximum_cluster_size: 10000

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
twist_topic: /sensing/vehicle_velocity_converter/twist_with_covariance
imu_topic: /sensing/imu/imu_data
gnss:
velocity_source_type: 2 # rtklib_msgs/RtklibNav: 0, nmea_msgs/Sentence: 1, ublox_msgs/NavPVT: 2, geometry_msgs/TwistWithCovarianceStamped: 3
velocity_source_type: 2 # rtklib_msgs/RtklibNav: 0, nmea_msgs/Sentence: 1, ublox_msgs/NavPVT: 2, geometry_msgs/TwistWithCovarianceStamped: 3, septentrio_gnss_driver/PVTGeodetic: 4
velocity_source_topic: /sensing/gnss/ublox/navpvt
llh_source_type: 2 # rtklib_msgs/RtklibNav: 0, nmea_msgs/Sentence: 1, sensor_msgs/NavSatFix: 2
llh_source_topic: /sensing/gnss/ublox/nav_sat_fix
Expand Down
5 changes: 5 additions & 0 deletions autoware_launch/config/localization/ekf_localizer.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,11 @@
pose_no_update_count_threshold_error: 100
twist_no_update_count_threshold_warn: 50
twist_no_update_count_threshold_error: 100
ellipse_scale: 3.0
error_ellipse_size: 1.5
warn_ellipse_size: 1.2
error_ellipse_size_lateral_direction: 0.3
warn_ellipse_size_lateral_direction: 0.25

misc:
# for velocity measurement limitation (Set 0.0 if you want to ignore)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
filter_settings:
# polygon overlap based filter
polygon_overlap_filter:
enabled: true
enabled: true
# velocity direction based filter
lanelet_direction_filter:
enabled: false
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,3 +9,13 @@
MOTORCYCLE : true
BICYCLE : true
PEDESTRIAN : true

filter_settings:
# polygon overlap based filter
polygon_overlap_filter:
enabled: true
# velocity direction based filter
lanelet_direction_filter:
enabled: false
velocity_yaw_threshold: 0.785398 # [rad] (45 deg)
object_speed_threshold: 3.0 # [m/s]
Original file line number Diff line number Diff line change
Expand Up @@ -5,13 +5,13 @@
resample_interval_for_planning: 0.3 # [m] FOR DEVELOPER
resample_interval_for_output: 4.0 # [m] FOR DEVELOPER

# avoidance module common setting
enable_bound_clipping: false
disable_path_update: false

# drivable lane setting. this module is able to use not only current lane but also right/left lane
# if the current lane(=lanelet::Lanelet) and the right/left lane share the boundary(=lanelet::Linestring) in HDMap.
# "current_lane" : use only current lane. this module doesn't use adjacent lane to avoid object.
# "same_direction_lane" : this module uses same direction lane to avoid object if need.
# "opposite_direction_lane": this module uses both same direction and opposite direction lane.
use_lane_type: "opposite_direction_lane"
# drivable area setting
use_adjacent_lane: true
use_opposite_lane: true
use_intersection_areas: true
use_hatched_road_markings: true
use_freespace_areas: true
Expand Down Expand Up @@ -178,6 +178,7 @@
safety_check_backward_distance: 100.0 # [m]
hysteresis_factor_expand_rate: 1.5 # [-]
hysteresis_factor_safe_count: 3 # [-]
collision_check_yaw_diff_threshold: 3.1416 # [rad]
# predicted path parameters
min_velocity: 1.38 # [m/s]
max_velocity: 50.0 # [m/s]
Expand Down Expand Up @@ -284,6 +285,19 @@
max_acceleration: 0.5 # [m/ss]
min_velocity_to_limit_max_acceleration: 2.78 # [m/ss]

# path generation method. select "shift_line_base" or "optimization_base" or "both".
# "shift_line_base" : Create avoidance path based on shift line.
# User can control avoidance maneuver execution via RTC.
# However, this method doesn't support complex avoidance scenario (e.g. S-shape maneuver).
# "optimization_base": This module selects avoidance target object
# and bpp module clips drivable area based on avoidance target object polygon shape.
# But this module doesn't modify the path shape.
# On the other hand, autoware_path_optimizer module optimizes path shape instead of this module
# so that the path can be within drivable area. This method is able to deal with complex avoidance scenario.
# However, user can't control avoidance manuever execution.
# "both" : Use both method.
path_generation_method: "shift_line_base"

shift_line_pipeline:
trim:
quantize_size: 0.1
Expand All @@ -293,8 +307,8 @@

# for debug
debug:
enable_other_objects_marker: false
enable_other_objects_info: false
enable_other_objects_marker: true
enable_other_objects_info: true
enable_detection_area_marker: false
enable_drivable_bound_marker: false
enable_safety_check_marker: false
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -182,6 +182,7 @@
time_horizon: 10.0
# hysteresis factor to expand/shrink polygon with the value
hysteresis_factor_expand_rate: 1.0
collision_check_yaw_diff_threshold: 3.1416
# temporary
backward_path_length: 30.0
forward_path_length: 100.0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
# safety check
safety_check:
allow_loose_check_for_cancel: true
collision_check_yaw_diff_threshold: 3.1416
execution:
expected_front_deceleration: -1.0
expected_rear_deceleration: -1.0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,79 +9,69 @@
enable_simultaneous_execution_as_candidate_module: true
keep_last: false
priority: 6
max_module_size: 1

external_request_lane_change_right:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: true
keep_last: false
priority: 6
max_module_size: 1

lane_change_left:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: true
keep_last: false
priority: 5
max_module_size: 1

lane_change_right:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: true
keep_last: false
priority: 5
max_module_size: 1

start_planner:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: false
keep_last: false
priority: 0
max_module_size: 1

side_shift:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: false
keep_last: false
priority: 2
max_module_size: 1

goal_planner:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: false
keep_last: true
priority: 1
max_module_size: 1

static_obstacle_avoidance:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: false
keep_last: false
priority: 4
max_module_size: 1

avoidance_by_lane_change:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: false
enable_simultaneous_execution_as_candidate_module: false
keep_last: false
priority: 3
max_module_size: 1

dynamic_obstacle_avoidance:
enable_rtc: false
enable_simultaneous_execution_as_approved_module: true
enable_simultaneous_execution_as_candidate_module: true
keep_last: true
priority: 7
max_module_size: 1

sampling_planner:
enable_module: true
Expand All @@ -90,4 +80,3 @@
enable_simultaneous_execution_as_candidate_module: false
keep_last: false
priority: 16
max_module_size: 1
Original file line number Diff line number Diff line change
Expand Up @@ -143,8 +143,10 @@
lateral_distance_max_threshold: 2.0
longitudinal_distance_min_threshold: 3.0
longitudinal_velocity_delta_time: 0.8
extended_polygon_policy: "along_path" # [-] select "rectangle" or "along_path"
# hysteresis factor to expand/shrink polygon
hysteresis_factor_expand_rate: 1.0
collision_check_yaw_diff_threshold: 1.578
# temporary
backward_path_length: 30.0
forward_path_length: 100.0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@
motorcycle: true
bicycle: true
pedestrian: true
pointcloud: false

cruise_obstacle_type:
inside:
Expand Down Expand Up @@ -68,8 +69,17 @@
motorcycle: true
bicycle: true
pedestrian: true
pointcloud: false

behavior_determination:
pointcloud_search_radius: 5.0
pointcloud_voxel_grid_x: 0.05
pointcloud_voxel_grid_y: 0.05
pointcloud_voxel_grid_z: 100000.0
pointcloud_cluster_tolerance: 1.0
pointcloud_min_cluster_size: 1
pointcloud_max_cluster_size: 100000

decimate_trajectory_step_length : 2.0 # longitudinal step length to calculate trajectory polygon for collision checking

prediction_resampling_time_interval: 0.1
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
<let name="latlon_controller_param_path_dir" value="$(var vehicle_id)" if="$(var use_individual_control_param)"/>
<let name="latlon_controller_param_path_dir" value="" unless="$(var use_individual_control_param)"/>

<include file="$(find-pkg-share tier4_control_launch)/launch/control.launch.py">
<include file="$(find-pkg-share tier4_control_launch)/launch/control.launch.xml">
<!-- option -->
<arg name="vehicle_param_file" value="$(find-pkg-share $(var vehicle_model)_description)/config/vehicle_info.param.yaml"/>
<arg name="use_multithread" value="true"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
<arg name="system_monitor_process_monitor_param_path" value="$(find-pkg-share autoware_launch)/config/system/system_monitor/process_monitor.param.yaml"/>
<arg name="system_monitor_voltage_monitor_param_path" value="$(find-pkg-share autoware_launch)/config/system/system_monitor/voltage_monitor.param.yaml"/>

<arg name="use_emergency_handler" value="true"/>
<arg name="use_emergency_handler" value="false"/>
<arg name="mrm_handler_param_path" value="$(find-pkg-share autoware_launch)/config/system/mrm_handler/mrm_handler.param.yaml"/>
<arg name="diagnostic_graph_aggregator_param_path" value="$(var diagnostic_graph_aggregator_param_path)"/>
<arg name="diagnostic_graph_aggregator_graph_path" value="$(var diagnostic_graph_aggregator_graph_path)"/>
Expand Down

0 comments on commit c52689c

Please sign in to comment.