This documentation is for a prerelease version of O3DE. Click here to switch to the latest release, or select a version from the dropdown.

Version:

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 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:

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 entities in various ways. It is can be thought as ROS 2 API to talk with :

  • Spawning and despawning,
  • setting and getting information about spawned entities,
  • getting predefined poses in simulated worlds,
  • pausing simulation,
  • resetting simulation,
  • controlling loaded level.

With SimulationInterfaces you can query and modify state of spawned entities and information about them. Spawned entity in SimulationInterfaces nomenclature is a single prefab spawned by spawn_entity service. There are no strict limitations about spawned prefab structure.

Although there is a recommendation to build your simulation assets in tree like structure where the root is a Rigid Body Component or Static Rigid Body and children are other components (like meshes, lights and others). In such case, mentioned root will be tracked as spawned entity

The correctly designed prefab should has following structure:
prefab

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. Simulation Interface will always set first simulated body as tracked entity if such exist in spawned prefab.

If spawned prefab does not have simulated bodies, prefab root a.k.a ContainerEntity will be tracked instead.

Note:
Object already existing on scene are not added to SimulationInterfaces Gem registry. Although, there is a C++ API which allows to add any entity to be maintained by the Gem.

The SimulationInterfaces allows performing 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.

Gem configuration

The SimulationInterfaces can be configured in your project with following registry keys:

Registry keyFeature
SimulationInterfaces/PrintStateNameInGuiIf set to true, the current state is shown in GUI
SimulationInterfaces/StartInStoppedStateBy default, simulation starts in stopped state. Setting to false allows starting simulation automatically
SimulationInterfaces/KeyboardTransitions/StoppedToPlayingSet the keyboard key that will change simulation state from Stopped to Playing e.g., keyboard_key_alphanumeric_R
SimulationInterfaces/KeyboardTransitions/PausedToPlayingSet the keyboard key that will change simulation state from Paused to Playing e.g., keyboard_key_alphanumeric_P
SimulationInterfaces/KeyboardTransitions/PlayingToPausedSet the keyboard key that will change simulation state from Playing to Paused e.g., keyboard_key_alphanumeric_P
ROS2SimulationInterfaces/<ServiceType>Change default service name (service is disabled if empty string is passed)
Note:
You can assign the same key to multiple SimulationInterfaces/KeyboardTransitions registry key.
Note:
The name of keyboard’s key to use (e.g., keyboard_key_alphanumeric_R) you can find in header InputDeviceKeyboard.h
Note:
ServiceType can be found in headers defining service handlers or in further part of this documentation.
Note:
More on registry in O3DE can be found in Settings Registry.

The sample registry file that you can put under directory <your_project>/Registry/simulationinterface_settings.setreg is listed below:

{
    "SimulationInterfaces": {
        "PrintStateNameInGui": true,
        "StartInStoppedState": true,
        "KeyboardTransitions":
        {
            "StoppedToPlaying": "keyboard_key_alphanumeric_R",
            "PausedToPlaying": "keyboard_key_alphanumeric_R",
            "PlayingToPaused": "keyboard_key_alphanumeric_P"
        }
    },
    "ROS2SimulationInterfaces": {
        "GetEntities": "custom_get_entities_service",
        "GetSimulatorFeatures": ""
    }
}

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: GetSimulatorFeatures.srv
SimulatorFeatures definition: SimulatorFeatures
Default service name: /get_simulator_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
  • NAMED_POSES
  • POSE_BOUNDS
  • ENTITY_TAGS
  • ENTITY_BOUNDS
  • ENTITY_BOUNDS_BOX
  • ENTITY_CATEGORIES
  • ENTITY_STATE_GETTING
  • ENTITY_STATE_SETTING
  • ENTITY_INFO_GETTING
  • ENTITY_INFO_SETTING
  • SPAWNABLES
  • SIMULATION_RESET
  • SIMULATION_RESET_TIME
  • SIMULATION_RESET_STATE
  • SIMULATION_RESET_SPAWNED
  • SIMULATION_STATE_GETTING
  • SIMULATION_STATE_SETTING
  • SIMULATION_STATE_PAUSE
  • STEP_SIMULATION_SINGLE
  • STEP_SIMULATION_MULTIPLE
  • STEP_SIMULATION_ACTION
  • WORLD_LOADING
  • WORLD_UNLOADING
  • WORLD_INFO_GETTING
  • AVAILABLE_WORLDS

SpawnEntity service

The SpawnEntity service lets you add simulated spawnables into the simulation environment. List of available spawnables can be obtained with the GetSpawnables service.

ROS 2 service definition: SpawnEntity.srv
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.

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 only entities which were previously spawned with the SimulationInterfaces interface.

GetNamedPoses service

The GetNamedPoses service allows you to get named poses defined in simulated world. To define NamedPose you need to add entity with NamedPoseEditorComponent in Editor and save it in you level prefab.

ROS 2 service definition: GetNamedPoses.srv
NamedPose definition: NamedPose.msg
Default service name: /get_named_poses
O3DE Ebus: SimulationInterfaces::NamedPoseManagerRequests::GetNamedPoses

GetNamedPoseBounds service

The GetNamedPoseBounds service allows you to get bounds of defined named pose. To define named pose bounds, entity with NamedPoseEditorComponent needs to have added collider.

ROS 2 service definition: GetNamedPoseBounds.srv
Default service name: /get_named_pose_bounds
O3DE Ebus: SimulationInterfaces::NamedPoseManagerRequests::GetNamedPoseBounds

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 allows to filter entities in the presented in the table below

Filter TypeHow filter works
regular expressionreturns only entities with names which matches passed regex
categoriesreturns entities which belong to given categories, to set category check out SetEntityInfo service
tagsreturns entities which are correctly tagged, to set entity tags check out SetEntityInfo service
boundsreturns result of Overlap Scene Query with simulation entities

Filters are combined with each other, so resulted entities fulfill all checks. If empty filters were passed, all simulated entities are returned.

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

GetEntityInfo service

The GetEntityInfo service allows to get information about entity such as category, description and tags.

ROS 2 service definition GetEntityInfo.srv
EntityInfo definition EntityInfo
Default service name: /get_entity_info
O3DE EBus: SimulationInterfaces::SimulationEntityManagerRequests::GetEntityInfo

SetEntityInfo service

The SetEntityInfo service allows to set information about entity such as category, description and tags.

ROS 2 service definition SetEntityInfo.srv
EntityInfo definition EntityInfo
Default service name: /set_entity_info
O3DE EBus: SimulationInterfaces::SimulationEntityManagerRequests::SetEntityInfo

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.srv
Individual spawnables ROS 2 message definition: Spawnable.msg
Default service name: /get_spawnables
O3DE EBus: SimulationInterfaces::SimulationEntityManagerRequests::GetSpawnables

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.

ScopePlanned API and usage
SCOPE_ALLReloading level using Level Manager
SCOPE_SPAWNEDInternal API to destroy all spawn tickets using Simulation Entities manager.
SCOPE_STATEMove all spawned entities to initial poses cached in Simulation Entities manager.
SCOPE_TIMENew 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.srv
SimulationState definition: SimulationState.msg
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.

The transition form NO_WORLD to PAUSED is triggered by loading level using /load_world service. Transition goes through LOADING_WORLD.

The transition from PLAYING or PAUSED is triggered by unloading level using /unload_world service.

The transition from NO_WORLD to PLAYING is 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.msg
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.

LoadWorld service

The LoadWorld service loads levels into the simulation. Calling the service with a loaded level unloads it before loading the requested level.

ROS 2 service definition: LoadWorld.srv
Default service name: /load_world
O3DE EBus: SimulationInterfaces::LevelManager::LoadWorld

Note The simulator currently doesn’t support loading levels from resource string.

UnloadWorld service

The UnloadWorld service unloads the current level from the simulation.

ROS 2 service definition: UnloadWorld.srv
Default service name: /unload_world
O3DE EBus: SimulationInterfaces::LevelManager::UnloadWorld

GetCurrentWorld service

The GetCurrentWorld service publishes information about the level that is currently loaded into the simulation.

ROS 2 service definition: GetCurrentWorld.srv
Default service name: /get_current_world
O3DE EBus: SimulationInterfaces::LevelManager::GetCurrentWorld

GetAvailableWorlds service

The GetAvailableWorlds service lists all available levels.

ROS 2 service definition: GetAvailableWorlds.srv
Default service name: /get_available_worlds
O3DE EBus: SimulationInterfaces::LevelManager::GetAvailableWorlds

Note The simulator doesn’t support searching for online resources.