IN THIS ARTICLE
SimulationInterfaces Gem
Overview
The SimulationInterfaces
Gem has been created to integrate O3DE with the ROS 2
simulation_interfaces package, which is a new standard for simulation usage. The new Gem contains the O3DE implementation together with the API based on the EBuses, as well as the ROS 2 interface to allow communication with O3DE via the ROS 2 framework.
Requirements
The SimulationInterfaces
Gem requires:
- ROS2 Gem version 3.3.0 or newer
- simulation_interfaces package installed.
Adding SimulationInterfaces Gem to the project
Add the SimulationInterfaces
Gem to the dependency list in the project.json
file to use it within your project. Gem’s functionality is implemented as System Components, hence making all interfaces available from the start.
To verify that the Gem has been added successfully, check the list of available ROS 2 services and actions after launching the GameLauncher (or running the Game Mode from the Editor).
Get available services command:
ros2 service list
Get available actions command:
ros2 action list
The details of the listed interfaces are provided in a later section.
Motivation
The SimulationInterfaces
is ROS 2 API that allows to affect simulated entities in various ways.
It is can be thought as ROS 2 API to talk with :
- Simulated Bodies,
- Spawning and despawning,
- pausing simulation,
- resetting simulation.
With SimulationInterfaces
you can query and modify state of simulated bodies.
Those are entities with components such as
Rigid Body Component or
Static Rigid Body and others.
Note:Entities that has no physics, will not be available bySimulationInterfaces
There is recommendation to build your simulation assets in tree like structure where the trunk is a Rigid Body Component or Static Rigid Body and children are other components (like meshes, lights and others).
The correctly designed prefab should has following structure:
The Rack
entity has
Static Rigid Body and
PhysX Mesh Collider Component and is available in SimulationInterfaces
.
Entities Boxes
, Lv0
, Lv1
, Lv2
are only decorative.
However, above-mentioned will follow Rack
, due to parent-child relation and
Transform Component.
The SimulationInterfaces
allows to perform bound search.
You can specify what is you region of interests and ask for Simulated Entities inside.
This feature uses
Overlap Scene Query.
You need to have collider shapes added to entities to get results from
Overlap Scene Query.
Note:The number of results in scene queries is pretty limited by default (32). We highly recommend to increase this limit to Overlap Query Buffer Size in PhysX Configuration.
Supported Features overview
This section presents the detailed description of the currently implemented and supported simulation features.
GetSimulatorFeatures service
The GetSimulatorFeatures
service allows users to get the list of
simulation_interfaces features that are supported by the simulator.
ROS 2 service definition:
GetEntityState.srv
SimulatorFeatures definition:
SimulatorFeatures
Default service name: /get_simulation_features
O3DE EBus: SimulationInterfaces::SimulationFeaturesAggregatorRequests::GetSimulationFeatures
The returned list contains numbers that can be mapped to the supported features. The mapping is defined in the SimulatorFeatures message.
The following features are currently supported:
- SPAWNING
- DELETING
- ENTITY_BOUNDS_BOX
- ENTITY_STATE_GETTING
- ENTITY_STATE_SETTING
- SPAWNABLES
- SIMULATION_RESET
- SIMULATION_RESET_TIME
- SIMULATION_RESET_SPAWNED
- SIMULATION_STATE_GETTING
- SIMULATION_STATE_SETTING
- SIMULATION_STATE_PAUSE
- STEP_SIMULATION_SINGLE
- STEP_SIMULATION_MULTIPLE
- STEP_SIMULATION_ACTION
GetSpawnables service
The GetSpawnables
service outputs a list of all simulated spawnables (e.g., models, robots, objects) that can be spawned into the simulation environment.
ROS 2 service definition:
GetSpawnables
Individual spawnables ROS 2 message definition:
Spawnable.msg
Default service name: /get_spawnables
O3DE EBus: SimulationInterfaces::SimulationEntityManagerRequests::GetSpawnables
SpawnEntity service
The SpawnEntity
service lets you add simulated spawnables into the simulation environment. As explained earlier, you can get the available spawnables with the GetSpawnables
service.
ROS 2 service definition:
SpawnEntity
Default service name: /spawn_entity
O3DE EBus: SimulationInterfaces::SimulationEntityManagerRequests::SpawnEntity
If you want to spawn a new object into the simulation environment, you need to know the valid URI of the spawnable, e.g.,product_asset:///prefabs/robot/foorobot.spawnable
. Simulation Entities Manager
will find corresponding Asset ID based on the URI.
Note: Spawning assets from the file system e.g., spawnable://home/username/robots/FooRobot.spawnables
is not supported.
GetEntities service
The GetEntities
service outputs a list of all spawned entities.
ROS 2 service definition:
GetEntities
EntityFilters definition:
EntityFilters
Default service name: /get_entities
O3DE EBus: SimulationInterfaces::SimulationEntityManagerRequests::GetEntities
This service works in two ways:
- returning to the caller whole cache of entities (when no filter in the query)
- returning results of Overlap Scene Query (when Bounds where set the query)
The intermediate result is filtered by the regular expression parameter (given in filter string) and the category.
Note: Filtering by tags is not yet supported.
GetEntitiesStates service
The GetEntitiesStates
service lets you get the state (speed, location, acceleration) of chosen entities.
ROS 2 service definition:
GetEntitiesStates.srv
Individual entity state ROS 2 message definition:
EntityState
Default service name: /get_entities_states
O3DE EBus: SimulationInterfaces::SimulationEntityManagerRequests::GetEntitiesStates
Note: Acceleration is not supported. Therefore, it is not filled in the response.
SetEntityState service
The SetEntityState
service lets you modify the state of the chosen entity. This includes the pose and the twist parameters.
ROS 2 service definition:
SetEntityState.srv
Individual entity state ROS 2 message definition:
EntityState
Default service name: /set_entity_state
O3DE EBus: SimulationInterfaces::SimulationEntityManagerRequests::SetEntityState
DeleteEntity service
The DeleteEntity
service lets you despawn the previously spawned entities.
ROS 2 service definition:
DeleteEntity.srv
Default service name: /delete_entity
O3DE EBus: SimulationInterfaces::SimulationEntityManagerRequests::DeleteEntity
Note: This mechanism allows you to delete the entities that are a part of the level prefab (e.g., prefab instantiated in Editor).
ResetSimulation service
The ResetSimulation
service lets you reset the simulation via ROS 2 interface.
ROS 2 service definition:
ResetSimulation.srv
Default service name: /reset_simulation
O3DE EBus: There is no additional interface for resetting the scene.
Scope | Planned API and usage |
---|---|
SCOPE_ALL | ConsoleRequestBus and LoadLevel command. |
SCOPE_SPAWNED | Internal API to destroy all spawn tickets using Simulation Entities manager . |
SCOPE_STATE | Move all spawned entities to initial poses cached in Simulation Entities manager . |
SCOPE_TIME | New call using ROS2Bus |
SetSimulationState service
The SetSimulationState
service lets you set the state of the simulation (STOPPED, PAUSED, PLAYING, QUITTING).
ROS 2 service definition:
SetSimulationState
SimulationState definition:
SimulationState
Default service name: /set_simulation_state
O3DE EBus: SimulationInterfaces::SimulationManagerRequests::SetSimulationState
The transition from PLAYING or PAUSED to STOPPED triggers level reloading.
The transition from PLAYING to PAUSED asks the default physics scene to be disabled. Hence, it stops movement of all PhysX articulations, rigid bodies (both kinematic and simulated), and characters. Some animations are played. The transition from PAUSED to PLAYING does the opposite.
The transition from PLAYING, PAUSED, or STOPPED to QUITTING closes simulator by calling quit
command over ConsoleRequestBus
.
Transitions from STOPPED to PAUSED and from QUITTING to any other state are forbidden.
GetSimulationState service
The GetSimulationState
service lets you get the current state of the simulation (PLAYING, PAUSED, or STOPPED).
ROS 2 service definition:
GetSimulationState.srv
SimulationState definition:
SimulationState
Default service name: /get_simulation_state
O3DE EBus: SimulationInterfaces::SimulationManagerRequests::GetSimulationState
GetEntityState service
The GetEntityState
service lets you get the state (speed, location, acceleration) of a single entity.
ROS 2 service definition:
GetEntityState.srv
Individual entity state ROS 2 message definition:
EntityState
Default service name: /get_entity_state
O3DE EBus: SimulationInterfaces::SimulationEntityManagerRequests::GetEntityState
Note: Acceleration is not supported. Therefore, it is not filled in the response.
StepSimulation service
The StepSimulation
service lets you simulate a finite number of steps.
ROS 2 service definition:
StepSimulation.srv
Default service name: /step_simulation
O3DE EBus: SimulationInterfaces::SimulationManagerRequests::StepSimulation
Note: The simulator has to be paused. Otherwise, StepSimulation
request will fail immediately.
SimulateSteps action
The SimulateSteps
action lets you simulate a finite number of steps in a non-blocking way.
Action definition:
SimulateSteps.action
Default action name: /simulate_steps
O3DE EBus: SimulationInterfaces::SimulationManagerRequests::StepSimulation
Note: The simulator has to be paused before calling this action. Otherwise, SimulateSteps
goal will be accepted and fail immediately.