ScenarioSimulatorConnection
Scenario Simulator Connection
is a scene setting for connecting Scenario Simulator v2
.
This page provides an overview of connecting to Scenario Simulator v2
and instruction of the scene.
Info
If you want to use OpenSCENARIO
with AWSIM
, see here.
Abstract
Scenario Simulator v2
(SS2
) is a scenario testing framework specifically developed for Autoware
.
It serves as a tool for Autoware
developers to conveniently create and execute scenarios across different simulators.
Scenario Simulator Connection
uses ZeroMQ
Inter-Process communication for seamless interaction between the AWSIM
and the SS2
.
To ensure synchronous operation of the SS2
, Scenario Simulator Connection
utilizes the Request/Reply
sockets provided by ZeroMQ
and exchanges binarized data through Protocol Buffers
.
This enables the SS2
to run in a synchronized manner, enhancing the accuracy and reliability of scenario testing.
Note
If you would like to see how SS2
works with Autoware
using default build-in simulator - simple_sensor_simulator
(without running AWSIM) - we encourage you to read this tutorial.
Overview
In the following sequence diagram describes responsible and communication of SS2
, AWSIM
and Autoware
.
Communication between SS2
and AWSIM
takes place via Request-Response
messages, and is as follows:
Launch
-Autoware
is started and initializedInitialize
- the environment inAWSIM
is initialized, basic parameters are setopt Ego spawn
- optional,EgoEntity
(with sensors) is spawned in the configuration defined in the scenarioopt NPC spawn loop
- optional, allEntities
(NPCs
) defined in the scenario are spawned, the scenario may contain any number of eachEntity
typeupdate loop
- this is the main loop where scenario commands are executed. It include updatingEgoEntity
,SS2
status,Entities
, simulation frame and traffic light statedespawn loop
- after the end of the scenario, allEntities
spawned on the scene are despawned (includingEgoEnity
)Terminate
- Autoware is terminated
Documentation of the commands used in the sequence is available here.
sequenceDiagram
participant ss2 as Scenario Simulator v2
participant awsim as AWSIM
participant aw as Autoware
ss2 ->> aw: Launch
ss2 ->>+ awsim: InitializeRequest
awsim -->>- ss2: InitializeResponse
opt Ego spawn
ss2 ->>+ awsim: SpawnVehicleEntityRequest
awsim -->>- ss2: SpawnVehicleEntityResponse
ss2 ->>+ awsim: AttachLidarSensorRequest
awsim -->>- ss2: AttachLidarSensorResponse
ss2 ->>+ awsim: AttachDetectionSensorRequest
awsim -->>- ss2: AttachDetectionSensorResponse
ss2 ->>+ awsim: AttachOccupancyGridSensorRequest
awsim -->>- ss2: AttachOccupancyGridSensorResponse
end
loop NPC spawn
opt Vehicle spawn
ss2 ->>+ awsim: SpawnVehicleEntityRequest
awsim -->>- ss2: SpawnVehicleEntityResponse
end
opt Pedestrian spawn
ss2 ->>+ awsim: SpawnPedestrianEntityRequest
awsim -->>- ss2: SpawnPedestrianEntityResponse
end
opt Misc Object spawn
ss2 ->>+ awsim: SpawnMiscObjectEntityRequest
awsim -->>- ss2: SpawnMiscObjectEntityResponse
end
end
loop update
opt Ego update
ss2 ->>+ awsim: UpdateEntityStatusRequest
awsim -->>- ss2: UpdateEntityStatusResponse
Note right of awsim: Request Ego status
end
opt Npc update
ss2 ->>+ awsim: UpdateEntityStatusRequest
awsim -->>- ss2: UpdateEntityStatusResponse
Note right of awsim: Request Npcs status
end
ss2 ->>+ awsim: UpdateFrameRequest
awsim ->>+ aw:
aw ->>- awsim: ROS2 Communication
awsim -->>- ss2: UpdateFrameResponse
ss2 ->>+ awsim: UpdateTrafficLightsRequest
awsim -->>- ss2: UpdateTrafficLightsResponse
end
loop despawn
ss2 ->>+ awsim: DespawnEntityRequest
awsim -->>- ss2: DespawnEntityResponse
end
ss2 ->> aw: Terminate
Configuration
Scenario Simulator Connection
can be configured from ScenarioSimulatorClient
component.
The configurable elements are listed in the following table:
Parameter | Description |
---|---|
Server Response Address | Tcp address to connect Scenario Simulator v2 . |
Traffic Lights In Scene | Traffic lights which is controlled. |
Entity Prefabs | List of Ego and Npc prefabs. Each element have identifier ( Asset Key ) and reference (Prefab ). |
Entites Root | Hierarchy where Npc spawn. |
Ego Follow Camera | Reference of Follow Camera object. |
Step Execution | Enable the checkbox to perform step execution. |
Step Duration In Percentage | On step execution, frames between each step. |
Instruction
To use Scenario Simulator Connection
, please follow the steps below.
For the preparation, the following must be prepared:
- 3D map (.fbx)
- lanelet map (.osm)
1. Placement and settings of ScenarioSimulatorClient
ScenarioSimulatorClient
component can mange and connect scenario simulation.
Please create and configure ScenarioSimulatorClient
component as the following:
- Create empty
GameObject
(should beFunction/ScenarioSimulatorClient
) - Attach this object to
ScenarioSimulatorClient
component - Fill in
Entities Root
field withScenarioSimulatorClient
object itself
2. Configuration of Entity Prefabs
Configure ScenarioSimulatorClient
to be able to use entity in Unity.
Please configure Entity Prefabs
field of ScenarioSimulatorClient
as the following:
- Fill in
Entity Prefabs
field with vehicle prefabs what you want to use- Fill
Asset Key
field with name for identifying prefab - Fill
Prefab
field with Ego and Npc prefab- Ego prefabs is in
Assets/Awsim/Prefabs/Entity/Npc/Vehicle/
- Npc prefabs is in
Assets/Awsim/Scenes/IntegrateScenarioSimulatorDemo/
- Ego prefabs is in
- Fill
3. Camera setting of ScenarioSimulatorClient
Add Camera
component in Unity scene to visualize scenario simulation in AWSIM
.
Please create and configure FollowCamera
component as the following:
- Create
Camera
object (should place onFunction/
) - Attach this object to
FollowCamera
component - Fill in
Ego FollowCamera
field ofScenarioSimulatorClient
with thisCamera
object
4. LaneletTrafficLight
settings
Attach and configure LaneletTrafficLight
script to all traffic light in the scene.
Please configure LaneletTrafficLight
components as the following:
- Attach
LaneletTrafficLight
to traffic light objects of all traffic light object in the scene - Modify
Bulb Material Config
as follow images
vehicle raffic light
pedestrian traffic light
- If there are wrong order of bulb, modify each
Bulb Material Config
- If there are wrong order of bulb, modify each
- Fill in
Traffic Lights In Scene
field ofScenarioSimulatorClient
with all traffic light object in the scene
Info
For detailed settings of Bulb Material Config
, see here.
5. Load lanelet
LaneletLoader
can load a lanelet map and set parameter of traffic rules to traffic lights.
LaneletLoader
can be performed by opening AWSIM -> Common -> Load Lanelet
at the toolbar of Unity Editor.
Please use LaneletLoader
as the following:
- Fill in
Osm
field with a lanelet map (.osm
) you prepared - Adjust
Waypoint settings
parameters for the loading process if needed - To load the lanelet map, please click
Load
button
- Delete
TrafficLanes
andStopLines
object what is generated byLaneletLoader
The Waypoint settings
parameters are listed in the following table:
Parameter | Description |
---|---|
Resolution | Resolution of resampling. Lower values provide better accuracy at the cost of processing time. |
Min Delta Length | Minimum length(m) between adjacent points. |
Min Delta Angle | Minimum angle(deg) between adjacent edges. Lowering this value produces a smoother curve. |
6. Placement of ClockRos2Publisher
Add ClockRos2Publisher
component to synchronize the ROS2 clock of AWSIM
and Scenario Simulator v2
.
Please create and configure ScenarioSimulatorClient
component as the following:
- Create empty
GameObject
(should beCommon/ClockRos2Publisher
) - Attach this object to
ClockRos2Publisher
component
7. Call methods of ScenarioSimulatorClient
and ClockRos2Publisher
Some methods of ScenarioSimulatorClient
and ClockRos2Publisher
should be called from callback of MonoBehaviour
to enable Scenario Simulator Client
.
Please implement as the following:
- Create or open class which is inherit
MonoBehaviour
- Make fields of
ScenarioSimulatorClient
andClockRos2Publisher
- Add description of calling method of
ScenarioSimulatorClient
andClockRos2Publisher
The method should be called are listed in the following table:
ScenarioSimulatorClient
Method | Description |
---|---|
Initialize() | Should be called Start() callback. |
OnUpdate() | Should be called Update() callback. |
OnFixedUpdate() | Should be called FixedUpdate() callback. |
ClockRos2Publisher
Method | Description |
---|---|
Initialize() | Should be called Start() callback. |
OnUpdate() | Should be called Update() callback. |
Info
AWSIM includes AutowareSimulationDemo
scene.
Please refer to:
* Assets/Awsim/Scenes/IntegrateScenarioSimulatorDemo/IntegrateScenarioSimulatorDemo.cs
* Assets/Awsim/Scenes/IntegrateScenarioSimulatorDemo.unity
scene
Scenario preparation
Scenario file should be modified to work Scenario Simulator v2
with AWSIM
.
Note that scenario file must be YAML file that follows TIER IV Scenario Format version 2.0
.
1. model3d
parameter
model3d
parameter must be added to Vehicle
parameter of scenario file to link prefabs in AWSIM
.
If value of model3d
corresponds to Asset Key
of ScenarioSimulatorClient
, the prefab is spawned in AWSIM
when scenario running.
The description example is as follows:
2. Entities parameters
Vehicle
parameter of scenario file should be match that of prefab in AWSIM
.
Especially, BoundingBox
parameter is crucial to validate the collisions correctly.
The entitiy parameters of default AWSIM
assets are listed in the following table:
Ego Vehicle Entity
model name | boundingbox size (m) | wheel base(m) | front tread(m) | rear tread(m) | tier diameter(m) | max steer(deg) |
---|---|---|---|---|---|---|
lexus_rx450h | width : 1.920 height : 1.700 length : 4.890 |
2.105 | 1.640 | 1.630 | 0.766 | 35 |
NPC Vehicle Entity
model name | boundingbox size (m) | wheel base(m) | front tread(m) | rear tread(m) | tier diameter(m) | max steer(deg) |
---|---|---|---|---|---|---|
taxi | width : 1.695 height : 1.515 length : 4.590 |
2.680 | 1.460 | 1.400 | 0.635 | 35 |
truck_2t | width : 1.695 height : 1.960 length : 4.685 |
2.490 | 1.395 | 1.240 | 0.673 | 40 |
hatchback | width : 1.695 height 1.515 length : 3.940 |
2.550 | 1.480 | 1.475 | 0.600 | 35 |
van | width : 1.880 height : 2.285 length : 4.695 |
2.570 | 1.655 | 1.650 | 0.600 | 35 |
small_car | width : 1.475 height 1.800 length : 3.395 |
2.520 | 1.305 | 1.305 | 0.557 | 35 |
NPC Pedestrian Entity
model name | boundingbox size (m) |
---|---|
human | width : 0.400 height : 1.800 length : 0.300 |
Misc Object Entity
model name | boundingbox size (m) |
---|---|
sign_board | width : 0.31 height : 0.58 length : 0.21 |
Note
If you use prefabs which is no listed above, you need to determine entities parameters by your 3d models.