|
31 | 31 | execute_num: 1 # [-]
|
32 | 32 | moving_speed_threshold: 1.0 # [m/s]
|
33 | 33 | moving_time_threshold: 2.0 # [s]
|
| 34 | + lateral_margin: |
| 35 | + soft_margin: 0.7 # [m] |
| 36 | + hard_margin: 0.3 # [m] |
| 37 | + hard_margin_for_parked_vehicle: 0.3 # [m] |
34 | 38 | max_expand_ratio: 0.0 # [-]
|
35 | 39 | envelope_buffer_margin: 0.5 # [m]
|
36 |
| - avoid_margin_lateral: 0.7 # [m] |
37 |
| - safety_buffer_lateral: 0.3 # [m] |
38 | 40 | safety_buffer_longitudinal: 0.0 # [m]
|
39 | 41 | use_conservative_buffer_longitudinal: true # [-] When set to true, the base_link2front is added to the longitudinal buffer before avoidance.
|
40 | 42 | truck:
|
41 | 43 | execute_num: 1
|
42 | 44 | moving_speed_threshold: 1.0 # 3.6km/h
|
43 | 45 | moving_time_threshold: 2.0
|
| 46 | + lateral_margin: |
| 47 | + soft_margin: 0.9 # [m] |
| 48 | + hard_margin: 0.1 # [m] |
| 49 | + hard_margin_for_parked_vehicle: 0.1 # [m] |
44 | 50 | max_expand_ratio: 0.0
|
45 | 51 | envelope_buffer_margin: 0.5
|
46 |
| - avoid_margin_lateral: 0.9 |
47 |
| - safety_buffer_lateral: 0.1 |
48 | 52 | safety_buffer_longitudinal: 0.0
|
49 | 53 | use_conservative_buffer_longitudinal: true
|
50 | 54 | bus:
|
51 | 55 | execute_num: 1
|
52 | 56 | moving_speed_threshold: 1.0 # 3.6km/h
|
53 | 57 | moving_time_threshold: 2.0
|
| 58 | + lateral_margin: |
| 59 | + soft_margin: 0.9 # [m] |
| 60 | + hard_margin: 0.1 # [m] |
| 61 | + hard_margin_for_parked_vehicle: 0.1 # [m] |
54 | 62 | max_expand_ratio: 0.0
|
55 | 63 | envelope_buffer_margin: 0.5
|
56 |
| - avoid_margin_lateral: 0.9 |
57 |
| - safety_buffer_lateral: 0.1 |
58 | 64 | safety_buffer_longitudinal: 0.0
|
59 | 65 | use_conservative_buffer_longitudinal: true
|
60 | 66 | trailer:
|
61 | 67 | execute_num: 1
|
62 | 68 | moving_speed_threshold: 1.0 # 3.6km/h
|
63 | 69 | moving_time_threshold: 2.0
|
| 70 | + lateral_margin: |
| 71 | + soft_margin: 0.9 # [m] |
| 72 | + hard_margin: 0.1 # [m] |
| 73 | + hard_margin_for_parked_vehicle: 0.1 # [m] |
64 | 74 | max_expand_ratio: 0.0
|
65 | 75 | envelope_buffer_margin: 0.5
|
66 |
| - avoid_margin_lateral: 0.9 |
67 |
| - safety_buffer_lateral: 0.1 |
68 | 76 | safety_buffer_longitudinal: 0.0
|
69 | 77 | use_conservative_buffer_longitudinal: true
|
70 | 78 | unknown:
|
71 | 79 | execute_num: 1
|
72 | 80 | moving_speed_threshold: 0.28 # 1.0km/h
|
73 | 81 | moving_time_threshold: 1.0
|
| 82 | + lateral_margin: |
| 83 | + soft_margin: 0.7 # [m] |
| 84 | + hard_margin: -0.2 # [m] |
| 85 | + hard_margin_for_parked_vehicle: -0.2 # [m] |
74 | 86 | max_expand_ratio: 0.0
|
75 | 87 | envelope_buffer_margin: 0.1
|
76 |
| - avoid_margin_lateral: 0.7 |
77 |
| - safety_buffer_lateral: -0.2 |
78 | 88 | safety_buffer_longitudinal: 0.0
|
79 | 89 | use_conservative_buffer_longitudinal: true
|
80 | 90 | bicycle:
|
81 | 91 | execute_num: 1
|
82 | 92 | moving_speed_threshold: 0.28 # 1.0km/h
|
83 | 93 | moving_time_threshold: 1.0
|
| 94 | + lateral_margin: |
| 95 | + soft_margin: 0.7 # [m] |
| 96 | + hard_margin: 0.5 # [m] |
| 97 | + hard_margin_for_parked_vehicle: 0.5 # [m] |
84 | 98 | max_expand_ratio: 0.0
|
85 | 99 | envelope_buffer_margin: 0.5
|
86 |
| - avoid_margin_lateral: 0.7 |
87 |
| - safety_buffer_lateral: 0.5 |
88 | 100 | safety_buffer_longitudinal: 1.0
|
89 | 101 | use_conservative_buffer_longitudinal: true
|
90 | 102 | motorcycle:
|
91 | 103 | execute_num: 1
|
92 | 104 | moving_speed_threshold: 1.0 # 3.6km/h
|
93 | 105 | moving_time_threshold: 1.0
|
| 106 | + lateral_margin: |
| 107 | + soft_margin: 0.7 # [m] |
| 108 | + hard_margin: 0.3 # [m] |
| 109 | + hard_margin_for_parked_vehicle: 0.3 # [m] |
94 | 110 | max_expand_ratio: 0.0
|
95 | 111 | envelope_buffer_margin: 0.5
|
96 |
| - avoid_margin_lateral: 0.7 |
97 |
| - safety_buffer_lateral: 0.3 |
98 | 112 | safety_buffer_longitudinal: 1.0
|
99 | 113 | use_conservative_buffer_longitudinal: true
|
100 | 114 | pedestrian:
|
101 | 115 | execute_num: 1
|
102 | 116 | moving_speed_threshold: 0.28 # 1.0km/h
|
103 | 117 | moving_time_threshold: 1.0
|
| 118 | + lateral_margin: |
| 119 | + soft_margin: 0.7 # [m] |
| 120 | + hard_margin: 0.5 # [m] |
| 121 | + hard_margin_for_parked_vehicle: 0.5 # [m] |
104 | 122 | max_expand_ratio: 0.0
|
105 | 123 | envelope_buffer_margin: 0.5
|
106 |
| - avoid_margin_lateral: 0.7 |
107 |
| - safety_buffer_lateral: 0.5 |
108 | 124 | safety_buffer_longitudinal: 1.0
|
109 | 125 | use_conservative_buffer_longitudinal: true
|
110 | 126 | lower_distance_for_polygon_expansion: 30.0 # [m]
|
|
0 commit comments