Skip to content

Commit

Permalink
feat(avoidance): configurable object type for safety check (autowaref…
Browse files Browse the repository at this point in the history
  • Loading branch information
satoshi-ota authored Nov 30, 2023
1 parent 2ea5274 commit 8f6ca92
Show file tree
Hide file tree
Showing 2 changed files with 33 additions and 16 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,6 @@
# avoidance is performed for the object type with true
target_object:
car:
is_target: true # [-]
execute_num: 1 # [-]
moving_speed_threshold: 1.0 # [m/s]
moving_time_threshold: 2.0 # [s]
Expand All @@ -40,7 +39,6 @@
safety_buffer_lateral: 0.3 # [m]
safety_buffer_longitudinal: 0.0 # [m]
truck:
is_target: true
execute_num: 1
moving_speed_threshold: 2.0 # 7.2km/h
moving_time_threshold: 2.0
Expand All @@ -50,7 +48,6 @@
safety_buffer_lateral: 0.1
safety_buffer_longitudinal: 0.0
bus:
is_target: true
execute_num: 1
moving_speed_threshold: 2.0 # 7.2km/h
moving_time_threshold: 2.0
Expand All @@ -60,7 +57,6 @@
safety_buffer_lateral: 0.1
safety_buffer_longitudinal: 0.0
trailer:
is_target: true
execute_num: 1
moving_speed_threshold: 2.0 # 7.2km/h
moving_time_threshold: 2.0
Expand All @@ -70,7 +66,6 @@
safety_buffer_lateral: 0.1
safety_buffer_longitudinal: 0.0
unknown:
is_target: true
execute_num: 1
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
Expand All @@ -80,7 +75,6 @@
safety_buffer_lateral: -0.2
safety_buffer_longitudinal: 0.0
bicycle:
is_target: true
execute_num: 1
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
Expand All @@ -90,7 +84,6 @@
safety_buffer_lateral: 0.5
safety_buffer_longitudinal: 1.0
motorcycle:
is_target: true
execute_num: 1
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
Expand All @@ -100,7 +93,6 @@
safety_buffer_lateral: 0.3
safety_buffer_longitudinal: 1.0
pedestrian:
is_target: true
execute_num: 1
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
Expand All @@ -114,6 +106,16 @@

# For target object filtering
target_filtering:
# avoidance target type
target_type:
car: true # [-]
truck: true # [-]
bus: true # [-]
trailer: true # [-]
unknown: true # [-]
bicycle: true # [-]
motorcycle: true # [-]
pedestrian: true # [-]
# params for avoidance of not-parked objects
threshold_time_force_avoidance_for_stopped_vehicle: 1.0 # [s]
object_ignore_section_traffic_light_in_front_distance: 100.0 # [m]
Expand All @@ -132,6 +134,16 @@

# For safety check
safety_check:
# safety check target type
target_type:
car: true # [-]
truck: true # [-]
bus: true # [-]
trailer: true # [-]
unknown: false # [-]
bicycle: true # [-]
motorcycle: true # [-]
pedestrian: true # [-]
# safety check configuration
enable: true # [-]
check_current_lane: false # [-]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@
# avoidance is performed for the object type with true
target_object:
car:
is_target: true # [-]
execute_num: 2 # [-]
moving_speed_threshold: 1.0 # [m/s]
moving_time_threshold: 1.0 # [s]
Expand All @@ -16,7 +15,6 @@
avoid_margin_lateral: 0.0 # [m]
safety_buffer_lateral: 0.0 # [m]
truck:
is_target: true
execute_num: 2
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
Expand All @@ -25,7 +23,6 @@
avoid_margin_lateral: 0.0
safety_buffer_lateral: 0.0
bus:
is_target: true
execute_num: 2
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
Expand All @@ -34,7 +31,6 @@
avoid_margin_lateral: 0.0
safety_buffer_lateral: 0.0
trailer:
is_target: true
execute_num: 2
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
Expand All @@ -43,7 +39,6 @@
avoid_margin_lateral: 0.0
safety_buffer_lateral: 0.0
unknown:
is_target: false
execute_num: 1
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
Expand All @@ -52,7 +47,6 @@
avoid_margin_lateral: 0.0
safety_buffer_lateral: 0.0
bicycle:
is_target: false
execute_num: 2
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
Expand All @@ -61,7 +55,6 @@
avoid_margin_lateral: 0.0
safety_buffer_lateral: 1.0
motorcycle:
is_target: false
execute_num: 2
moving_speed_threshold: 1.0 # 3.6km/h
moving_time_threshold: 1.0
Expand All @@ -70,7 +63,6 @@
avoid_margin_lateral: 0.0
safety_buffer_lateral: 1.0
pedestrian:
is_target: false
execute_num: 2
moving_speed_threshold: 0.28 # 1.0km/h
moving_time_threshold: 1.0
Expand All @@ -80,3 +72,16 @@
safety_buffer_lateral: 1.0
lower_distance_for_polygon_expansion: 0.0 # [m]
upper_distance_for_polygon_expansion: 1.0 # [m]

# For target object filtering
target_filtering:
# avoidance target type
target_type:
car: true # [-]
truck: true # [-]
bus: true # [-]
trailer: true # [-]
unknown: true # [-]
bicycle: false # [-]
motorcycle: false # [-]
pedestrian: false # [-]

0 comments on commit 8f6ca92

Please sign in to comment.