-
Notifications
You must be signed in to change notification settings - Fork 60
/
sample.yaml
174 lines (174 loc) · 6.56 KB
/
sample.yaml
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
ScenarioModifiers:
ScenarioModifier:
- name: LANE_ID
list: [34513, 34510, 34564]
OpenSCENARIO:
FileHeader:
author: 'Tatsuya Yamasaki'
date: '2022-03-04T18:06:53+09:00'
description: 'Sample scenario (with Autoware)'
revMajor: 1
revMinor: 0
ParameterDeclarations:
ParameterDeclaration:
- name: random_offset
parameterType: double
value: $(ros2 run openscenario_interpreter_example uniform_distribution -1.0 1.0)
ConstraintGroup:
- ValueConstraint:
- rule: lessOrEqual
value: 1.0
- rule: greaterOrEqual
value: -1.0
CatalogLocations:
VehicleCatalog:
Directory:
path: $(ros2 pkg prefix --share openscenario_experimental_catalog)/vehicle
RoadNetwork:
LogicFile:
filepath: $(ros2 pkg prefix --share kashiwanoha_map)/map
Entities:
ScenarioObject:
- name: ego
CatalogReference:
catalogName: sample_vehicle
entryName: sample_vehicle
ObjectController:
Controller:
name: 'Autoware'
Properties:
Property:
- name: maxJerk
value: "1.5"
- name: minJerk
value: "-1.5"
Storyboard:
Init:
Actions:
Private:
- entityRef: ego
PrivateAction:
- TeleportAction:
Position:
LanePosition:
roadId: ''
laneId: LANE_ID
s: 1
offset: $random_offset
Orientation:
type: relative
h: 0
p: 0
r: 0
- RoutingAction:
AcquirePositionAction:
Position:
LanePosition:
roadId: ''
laneId: '34507'
s: 50
offset: 0
Orientation:
type: relative
h: 0
p: 0
r: 0
Story:
- name: ''
Act:
- name: _EndCondition
ManeuverGroup:
- maximumExecutionCount: 1
name: ''
Actors:
selectTriggeringEntities: false
EntityRef:
- entityRef: ego
Maneuver:
- name: ''
Event:
- name: ''
priority: parallel
StartTrigger:
ConditionGroup:
- Condition:
- name: ''
delay: 0
conditionEdge: none
ByEntityCondition:
TriggeringEntities:
triggeringEntitiesRule: any
EntityRef:
- entityRef: ego
EntityCondition:
ReachPositionCondition:
Position:
LanePosition:
roadId: ''
laneId: '34507'
s: 50
offset: 0
Orientation:
type: relative
h: 0
p: 0
r: 0
tolerance: 0.5
- name: ''
delay: 0
conditionEdge: none
ByValueCondition:
UserDefinedValueCondition:
name: RelativeHeadingCondition(ego, 34507, 50)
rule: lessThan
value: 0.1
- name: ''
delay: 0
conditionEdge: none
ByValueCondition:
UserDefinedValueCondition:
name: RelativeHeadingCondition(ego)
rule: lessThan
value: 0.1
- name: ''
delay: 0
conditionEdge: none
ByValueCondition:
UserDefinedValueCondition:
name: ego.currentMinimumRiskManeuverState.state
rule: equalTo
value: NORMAL
Action:
- name: ''
UserDefinedAction:
CustomCommandAction:
type: exitSuccess
- name: ''
priority: parallel
StartTrigger:
ConditionGroup:
- Condition:
- name: ''
delay: 0
conditionEdge: none
ByValueCondition:
SimulationTimeCondition:
value: 180
rule: greaterThan
Action:
- name: ''
UserDefinedAction:
CustomCommandAction:
type: exitFailure
StartTrigger:
ConditionGroup:
- Condition:
- name: ''
delay: 0
conditionEdge: none
ByValueCondition:
SimulationTimeCondition:
value: 0
rule: greaterThan
StopTrigger:
ConditionGroup: []