Skip to content

Commit

Permalink
Merge pull request autowarefoundation#191 from tier4/sync-awf-upstream
Browse files Browse the repository at this point in the history
chore: sync awf/autoware_launch
  • Loading branch information
tier4-autoware-public-bot[bot] authored Jun 26, 2023
2 parents 8ced2b5 + da90008 commit 5c3ffa2
Show file tree
Hide file tree
Showing 8 changed files with 47 additions and 10 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
/**:
ros__parameters:
binary_bayes_filter:
probability_matrix:
occupied_to_occupied: 0.95
occupied_to_free: 0.05
free_to_occupied: 0.2
free_to_free: 0.8
v_ratio: 10.0
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,14 @@
# ray-tracing center: main sensor frame is preferable like: "velodyne_top"
scan_origin_frame: "base_link"

use_height_filter: true
height_filter:
use_height_filter: true
min_height: -1.0
max_height: 2.0

enable_single_frame_mode: false
map_length: 150.0
map_width: 150.0
map_resolution: 0.5

updater_type: "binary_bayes_filter" # binary_bayes_filter, etc.
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,11 @@
map_length: 150.0 # [m]
map_resolution: 0.5 # [m]

use_height_filter: true
height_filter:
use_height_filter: true
min_height: -1.0
max_height: 2.0

enable_single_frame_mode: false
# use sensor pointcloud to filter obstacle pointcloud
filter_obstacle_pointcloud_by_raw_pointcloud: false
Expand All @@ -15,3 +19,5 @@
gridmap_origin_frame: "base_link"
# ray-tracing center: main sensor frame is preferable like: "velodyne_top"
scan_origin_frame: "base_link"

updater_type: "binary_bayes_filter" # binary_bayes_filter, etc.
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@
moving_time_threshold: 1.0 # [s]
max_expand_ratio: 0.0 # [-]
envelope_buffer_margin: 0.3 # [m]
avoid_margin_lateral: 1.0 # [m]
safety_buffer_lateral: 0.7 # [m]
safety_buffer_longitudinal: 0.0 # [m]
truck:
Expand All @@ -41,6 +42,7 @@
moving_time_threshold: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.3
avoid_margin_lateral: 1.0
safety_buffer_lateral: 0.7
safety_buffer_longitudinal: 0.0
bus:
Expand All @@ -49,6 +51,7 @@
moving_time_threshold: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.3
avoid_margin_lateral: 1.0
safety_buffer_lateral: 0.7
safety_buffer_longitudinal: 0.0
trailer:
Expand All @@ -57,38 +60,43 @@
moving_time_threshold: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.3
avoid_margin_lateral: 1.0
safety_buffer_lateral: 0.7
safety_buffer_longitudinal: 0.0
unknown:
enable: false
enable: true
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.3
avoid_margin_lateral: 1.0
safety_buffer_lateral: 0.7
safety_buffer_longitudinal: 0.0
bicycle:
enable: false
enable: true
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.8
avoid_margin_lateral: 1.0
safety_buffer_lateral: 1.0
safety_buffer_longitudinal: 1.0
motorcycle:
enable: false
enable: true
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.8
avoid_margin_lateral: 1.0
safety_buffer_lateral: 1.0
safety_buffer_longitudinal: 1.0
pedestrian:
enable: false
enable: true
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
max_expand_ratio: 0.0
envelope_buffer_margin: 0.8
avoid_margin_lateral: 1.0
safety_buffer_lateral: 1.0
safety_buffer_longitudinal: 1.0
lower_distance_for_polygon_expansion: 30.0 # [m]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@

lateral_distance_max_threshold: 1.7
longitudinal_distance_min_threshold: 3.0
longitudinal_velocity_delta_time: 0.3
longitudinal_velocity_delta_time: 0.8

expected_front_deceleration: -1.0
expected_rear_deceleration: -1.0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,9 @@
motorcycle: true
pedestrian: false

min_obstacle_vel: 1.0 # [m/s]
min_obstacle_vel: 0.0 # [m/s]

successive_num_to_entry_dynamic_avoidance_condition: 5

drivable_area_generation:
lat_offset_from_obstacle: 0.8 # [m]
Expand All @@ -22,11 +24,11 @@
overtaking_object:
max_time_to_collision: 3.0 # [s]
start_duration_to_avoid: 4.0 # [s]
end_duration_to_avoid: 5.0 # [s]
end_duration_to_avoid: 8.0 # [s]
duration_to_hold_avoidance: 3.0 # [s]

# for opposite directional object
oncoming_object:
max_time_to_collision: 3.0 # [s]
start_duration_to_avoid: 9.0 # [s]
start_duration_to_avoid: 12.0 # [s]
end_duration_to_avoid: 0.0 # [s]
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
<?xml version="1.0"?>
<launch>
<arg name="occupancy_grid_map_method" default="pointcloud_based_occupancy_grid_map" description="options: pointcloud_based_occupancy_grid_map, laserscan_based_occupancy_grid_map"/>
<arg name="occupancy_grid_map_updater" default="binary_bayes_filter" description="options: binary_bayes_filter"/>

<include file="$(find-pkg-share tier4_perception_launch)/launch/perception.launch.xml">
<arg name="mode" value="$(var perception_mode)"/>
Expand Down Expand Up @@ -36,5 +37,7 @@
/>
<arg name="occupancy_grid_map_method" value="$(var occupancy_grid_map_method)"/>
<arg name="occupancy_grid_map_param_path" value="$(find-pkg-share autoware_launch)/config/perception/occupancy_grid_map/$(var occupancy_grid_map_method).param.yaml"/>
<arg name="occupancy_grid_map_updater" value="$(var occupancy_grid_map_updater)"/>
<arg name="occupancy_grid_map_updater_param_path" value="$(find-pkg-share autoware_launch)/config/perception/occupancy_grid_map/$(var occupancy_grid_map_updater)_updater.param.yaml"/>
</include>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
<arg name="vehicle_model"/>
<arg name="initial_engage_state"/>
<arg name="vehicle_info_param_file"/>
<arg name="occupancy_grid_map_updater" default="binary_bayes_filter" description="options: binary_bayes_filter"/>

<include file="$(find-pkg-share tier4_simulator_launch)/launch/simulator.launch.xml">
<arg name="launch_dummy_perception" value="$(var launch_dummy_perception)"/>
Expand All @@ -37,5 +38,7 @@
<arg name="pose_initializer_common_param_path" value="$(find-pkg-share autoware_launch)/config/localization/pose_initializer_common.param.yaml"/>
<arg name="pose_initializer_param_path" value="$(find-pkg-share autoware_launch)/config/localization/pose_initializer.planning_simulator.param.yaml"/>
<arg name="laserscan_based_occupancy_grid_map_param_path" value="$(find-pkg-share autoware_launch)/config/perception/occupancy_grid_map/laserscan_based_occupancy_grid_map.param.yaml"/>
<arg name="occupancy_grid_map_updater" value="$(var occupancy_grid_map_updater)"/>
<arg name="occupancy_grid_map_updater_param_path" value="$(find-pkg-share autoware_launch)/config/perception/occupancy_grid_map/$(var occupancy_grid_map_updater)_updater.param.yaml"/>
</include>
</launch>

0 comments on commit 5c3ffa2

Please sign in to comment.