Skip to content
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
Show all changes
33 commits
Select commit Hold shift + click to select a range
5267ea2
simulation interfaces
adamdbrw Dec 17, 2024
0cfd0fd
Apply suggestions from code review
adamdbrw Dec 19, 2024
d874c23
applied review suggestions
adamdbrw Dec 19, 2024
10f59d2
added missing cmake entries
adamdbrw Dec 19, 2024
ea23f59
stepping service
adamdbrw Dec 19, 2024
97b79f7
robot_namespace -> namespace
adamdbrw Dec 19, 2024
8bae938
changed filter semantics to regex
adamdbrw Dec 19, 2024
885a3fa
Updated EntityState and SpawnableBounds messages to address feedback
adamdbrw Jan 7, 2025
53d6ee9
Added action for multi-stepping
adamdbrw Jan 7, 2025
aaee904
Added stepping alternatives documentation
adamdbrw Jan 7, 2025
df98b24
Added GetSimulatorFeatures interface
adamdbrw Jan 7, 2025
4d551f1
Apply suggestions from code review
adamdbrw Jan 13, 2025
95f46d9
Update srv/GetEntityState.srv
adamdbrw Jan 14, 2025
0169e10
Code review improvements:
adamdbrw Jan 14, 2025
1e92784
Apply suggestions from code review
adamdbrw Jan 20, 2025
9bf757f
Revision following the review:
adamdbrw Jan 20, 2025
e94797f
Added sources field; documentation changes
adamdbrw Jan 24, 2025
eabed90
Update action/MultiStepSimulation.action
adamdbrw Feb 5, 2025
271a8a1
Modified result handling and entity info, tags and categories
adamdbrw Feb 5, 2025
9ec77e6
Apply suggestions from code review
adamdbrw Feb 6, 2025
86ea8e0
Addressing review:
adamdbrw Feb 6, 2025
9d123ed
Addressing review comments:
adamdbrw Feb 7, 2025
a940c65
Review comments applied:
adamdbrw Feb 10, 2025
aee7e79
Update msg/SimulationState.msg
adamdbrw Feb 18, 2025
4497cbc
Apply suggestions from code review
adamdbrw Mar 3, 2025
af3ebff
Applied review comments:
adamdbrw Mar 3, 2025
5f0aefb
corrected entities to strings
adamdbrw Mar 4, 2025
5fe0d30
Update msg/Bounds.msg
adamdbrw Mar 17, 2025
eb6f27e
Applied review
adamdbrw Mar 17, 2025
e98721f
Applied review
adamdbrw Mar 18, 2025
65a653f
feature naming fix
adamdbrw Mar 18, 2025
4e6867d
Update srv/SetEntityState.srv
adamdbrw Mar 20, 2025
2206c58
Update srv/SetEntityState.srv
adamdbrw Mar 20, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions action/SimulateSteps.action
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
# Assuming the simulation is paused, simulate a finite number of steps and return to paused state.
# The action returns feedback after each complete step.
# For a service alternative, see StepSimulation, which often makes more sense when doing a single step (steps = 1).
# Support for this interface is indicated through the STEP_SIMULATION_ACTION value in GetSimulationFeatures.

uint64 steps # Action goal: step through the simulation loop this many times.
---
Expand Down
2 changes: 1 addition & 1 deletion msg/Bounds.msg
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
# Certain goals or points might be valid for a small object, but not suitable for a large one,
# or a differently shaped one.
# Bounds can be also checked to ensure certain scenario conditions are met.
# For entities, these limits are relative to entity's top link transform, following ROS rep-103 convention.
# For entities, these limits are relative to entity's canonical link transform, following ROS rep-103 convention.

# As bounds are optional in most interfaces, TYPE_EMPTY signifies empty bounds, to be understood as "unbounded".
# Otherwise, the fields are expected to define a valid volume.
Expand Down
19 changes: 11 additions & 8 deletions msg/EntityCategory.msg
Original file line number Diff line number Diff line change
@@ -1,13 +1,16 @@
# Entity major category, which often warrants a specific way to handle such entity, e.g. when handling humans
# or mapping persistence for dynamic vs static objects.

uint8 OBJECT = 0 # Generic or unspecified type.
uint8 ROBOT = 1 # A broad category for mobile robots, arms, drones etc., usually with ROS 2 interfaces.
uint8 HUMAN = 2 # Simulated humans, e.g. pedestrians, warehouse workers. Compared to DYNAMIC_OBJECT category,
# humans are often expected to be treated exceptionally in regards to safety constraints.
uint8 DYNAMIC_OBJECT = 4 # Vehicles, animals, mobile obstacles, typically to present a detection & tracking challenge,
# such as when simulation is used to test robot perception or navigation stack.
uint8 STATIC_OBJECT = 5 # Any object which is static, e.g. not supposed to change its pose
# unless by means of SetEntityState.
uint8 CATEGORY_OBJECT = 0 # Generic or unspecified type.
uint8 CATEGORY_ROBOT = 1 # A broad category for mobile robots, arms, drones etc.,
# usually with ROS 2 interfaces.
uint8 CATEGORY_HUMAN = 2 # Simulated humans, e.g. pedestrians, warehouse workers.
# Compared to CATEGORY_DYNAMIC_OBJECT, humans are often expected to be treated
# exceptionally in regards to safety constraints.
uint8 CATEGORY_DYNAMIC_OBJECT = 4 # Vehicles, animals, mobile obstacles, typically to present a detection and
# tracking challenge, such as when simulation is used to test robot perception
# or navigation stack.
uint8 CATEGORY_STATIC_OBJECT = 5 # Any object which is static, e.g. not supposed to change its pose
# unless by means of SetEntityState.

uint8 category
17 changes: 11 additions & 6 deletions msg/EntityFilters.msg
Original file line number Diff line number Diff line change
Expand Up @@ -10,11 +10,16 @@ EntityCategory[] categories # Optional, defaults to empt
# Entities matching any of the categories will be returned.
# To get entity category, use GetEntityInfo.
# Applies together with other filters (filter, tags).
# Check ENTITY_CATEGORIES in GetSimulatorFeatures to determine if
# your simulator supports entity categories.
TagsFilter tags # Tags filter to apply. To get entity tags, use GetEntityInfo.
# Applies together with other filters (filter, categories).

# if bounds are not empty, the overlap filter is applied and entities overlapping with bounds will be returned.
# Note that not all bound types might be supported by the simulator, though at least TYPE_SPHERE needs to be supported.
# If service is called with filter bounds set to an unsupported type, a FEATURE_UNSUPPORTED result will be returned.

Bounds bounds
# Check support for this feature (ENTITY_TAGS) in GetSimulationFeatures.
Bounds bounds # if bounds are not empty, the overlap filter is applied
# and entities overlapping with bounds will be returned.
# Note that not all bound types might be supported by the simulator,
# though at least TYPE_SPHERE needs to be supported.
# Check ENTITY_BOUNDS_BOX and ENTITY_BOUNDS_CONVEX in GetSimulationFeatures
# to determine whether your simulator supports other bound types.
# If service is called with filter bounds set to an unsupported type,
# a FEATURE_UNSUPPORTED result will be returned.
28 changes: 14 additions & 14 deletions msg/Result.msg
Original file line number Diff line number Diff line change
@@ -1,18 +1,18 @@
# Result code and message for service calls.
# Note that additional results for specific services can defined within them using values above 100.

uint8 FEATURE_UNSUPPORTED = 0 # Feature is not supported by the simulator, check GetSimulatorFeatures.
# While feature support can sometimes be deduced from presence of corresponding
# service / action interface, in other cases it is about supporting certain call
# parameters, formats and options within interface call.
uint8 OK = 1
uint8 NOT_FOUND = 2 # No match for input (such as when entity name does not exist).
uint8 INCORRECT_STATE = 3 # Simulator is in an incorrect state for this interface call, e.g. a service
# requires paused state but the simulator is not paused.
uint8 OPERATION_FAILED = 4 # Request could not be completed successfully even though feature is supported and
# the input is correct; check error_message for details.
# Implementation rule: check extended codes for called service (e.g. SpawnEntity)
# to provide a return code which is more specific.
uint8 RESULT_FEATURE_UNSUPPORTED = 0 # Feature is not supported by the simulator, check GetSimulatorFeatures.
# While feature support can sometimes be deduced from presence of corresponding
# service / action interface, in other cases it is about supporting certain
# call parameters, formats and options within interface call.
uint8 RESULT_OK = 1
uint8 RESULT_NOT_FOUND = 2 # No match for input (such as when entity name does not exist).
uint8 RESULT_INCORRECT_STATE = 3 # Simulator is in an incorrect state for this interface call, e.g. a service
# requires paused state but the simulator is not paused.
uint8 RESULT_OPERATION_FAILED = 4 # Request could not be completed successfully even though feature is supported
# and the input is correct; check error_message for details.
# Implementation rule: check extended codes for called service
# (e.g. SpawnEntity) to provide a return code which is more specific.

uint8 result # Result to be checked on return from service interface call
string error_message # Additional error description when useful.
uint8 result # Result to be checked on return from service interface call
string error_message # Additional error description when useful.
10 changes: 5 additions & 5 deletions msg/SimulationState.msg
Original file line number Diff line number Diff line change
@@ -1,14 +1,14 @@
# Simulation states used in SetSimulationState and returned in GetSimulationState

uint8 STOPPED = 0 # Simulation is stopped, which is equivalent to pausing and resetting with ALL.
uint8 STATE_STOPPED = 0 # Simulation is stopped, which is equivalent to pausing and resetting with ALL.
# This is typically the default state when simulator is launched.
# Stopped simulation can be played. It can also be paused, which means
# starting simulation in a paused state immediately,
# without any time steps for physics or simulated clock ticks.
uint8 PLAYING = 1 # Simulation is playing, can be either paused or stopped.
uint8 PAUSED = 2 # Simulation is paused, can be either stopped (which will reset it) or played.
uint8 QUITTING = 3 # Closing the simulator application. Switching from PLAYING or PAUSED states
# is expected to stop the simulation first, and then exit.
uint8 STATE_PLAYING = 1 # Simulation is playing, can be either paused or stopped.
uint8 STATE_PAUSED = 2 # Simulation is paused, can be either stopped (which will reset it) or played.
uint8 STATE_QUITTING = 3 # Closing the simulator application. Switching from STATE_PLAYING or STATE_PAUSED
# states is expected to stop the simulation first, and then exit.
# Simulation interfaces will become unavailable after quitting.
# Running simulation application is outside of the simulation interfaces as
# there is no service to handle the call when the simulator is not up.
Expand Down
45 changes: 26 additions & 19 deletions msg/SimulatorFeatures.msg
Original file line number Diff line number Diff line change
@@ -1,31 +1,38 @@
# Features supported by the simulator.

uint8 SPAWNING = 0 # Supports spawn interface (SpawnEntity).
uint8 DELETING = 1 # Supports deleting entities (DeleteEntity).
uint8 NAMED_POSES = 2 # Supports predefined named poses (GetNamedPoses).
uint8 POSE_BOUNDS = 3 # Supports pose bounds (GetNamedPoseBounds).
uint8 ENTITY_TAGS = 4 # Supports entity tags in interfaces using EntityFilters, such as GetEntities.
uint8 ENTITY_BOUNDS = 5 # Supports entity bounds (GetEntityBounds).
uint8 ENTITY_BOUNDS_CONVEX = 6 # Supports entity filtering with Bounds TYPE_CONVEX_HULL.
uint8 SPAWNING_RESOURCE_STRING = 7 # Supports SpawnEntity resource_string field.
uint8 SPAWNING = 0 # Supports spawn interface (SpawnEntity).
uint8 DELETING = 1 # Supports deleting entities (DeleteEntity).
uint8 NAMED_POSES = 2 # Supports predefined named poses (GetNamedPoses).
uint8 POSE_BOUNDS = 3 # Supports pose bounds (GetNamedPoseBounds).
uint8 ENTITY_TAGS = 4 # Supports entity tags in interfaces using EntityFilters, such as GetEntities.
uint8 ENTITY_BOUNDS = 5 # Supports entity bounds (GetEntityBounds).
uint8 ENTITY_BOUNDS_BOX = 6 # Supports entity filtering with bounds with TYPE_BOX.
uint8 ENTITY_BOUNDS_CONVEX = 7 # Supports entity filtering with Bounds TYPE_CONVEX_HULL.
uint8 ENTITY_CATEGORIES = 8 # Supports entity categories, such as in use with EntityFilters or SetEntityInfo.
uint8 SPAWNING_RESOURCE_STRING = 9 # Supports SpawnEntity resource_string field.

uint8 ENTITY_STATE_LISTING = 10 # Supports GetEntityState interface.
uint8 ENTITY_STATE_GETTING = 10 # Supports GetEntityState interface.
uint8 ENTITY_STATE_SETTING = 11 # Supports SetEntityState interface.
uint8 ENTITY_INFO_SETTING = 12 # Supports SetEntityInfo interface.
uint8 ENTITY_INFO_GETTING = 12 # Supports GetEntityInfo interface.
uint8 ENTITY_INFO_SETTING = 13 # Supports SetEntityInfo interface.
uint8 SPAWNABLES = 14 # Supports GetSpawnables interface.

uint8 SIMULATION_RESET = 20 # Supports one or more ways to reset the simulation through ResetSimulation.
uint8 SIMULATION_RESET_TIME = 21 # Supports TIME flag for resetting.
uint8 SIMULATION_RESET_STATE = 22 # Supports STATE flag for resetting.
uint8 SIMULATION_RESET_SPAWNED = 23 # Supports SPAWNED flag for resetting.
uint8 SIMULATION_RESET_TIME = 21 # Supports SCOPE_TIME flag for resetting.
uint8 SIMULATION_RESET_STATE = 22 # Supports SCOPE_STATE flag for resetting.
uint8 SIMULATION_RESET_SPAWNED = 23 # Supports SCOPE_SPAWNED flag for resetting.
uint8 SIMULATION_STATE_GETTING = 24 # Supports GetSimulationState interface.
uint8 SIMULATION_STATE_SETTING = 25 # Supports SetSimulationState interface. Check SIMULATION_STATE_PAUSE feature
# for setting STATE_PAUSED.
uint8 SIMULATION_STATE_PAUSE = 26 # Supports the STATE_PAUSED SimulationState in SetSimulationState interface.

uint8 SIMULATION_PAUSE = 30 # Supports the PAUSED SimulationState in SetSimulationState interface.
uint8 STEP_SIMULATION_SINGLE = 31 # Supports single stepping through simulation with StepSimulation interface.
uint8 STEP_SIMULATION_MULTIPLE = 32 # Supports multi-stepping through simulation, either through StepSimulation.
# service or through SimulateSteps action.
uint8 STEP_SIMULATION_ACTION = 33 # Supports SimulateSteps action interface.
uint8 STEP_SIMULATION_SINGLE = 31 # Supports single stepping through simulation with StepSimulation interface.
uint8 STEP_SIMULATION_MULTIPLE = 32 # Supports multi-stepping through simulation, either through StepSimulation.
# service or through SimulateSteps action.
uint8 STEP_SIMULATION_ACTION = 33 # Supports SimulateSteps action interface.


uint16[] features # A list of simulation features as specified by the list above.
uint16[] features # A list of simulation features as specified by the list above.

# A list of additional supported formats for spawning, which might be empty. Values may include
# * sdf (SDFormat)
Expand Down
6 changes: 3 additions & 3 deletions msg/TagsFilter.msg
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
# An utility message type for specification of tag-based filtering

string[] tags # Optional, defaults to empty, which means no tags filter.
# Results matching any or all of tags will be returned, depending
# on tags_filter_mode.
string[] tags # Optional, defaults to empty, which means no tags filter.
# Results matching any or all of tags will be returned, depending
# on tags_filter_mode.

uint8 FILTER_MODE_ANY = 0 # Filter with OR mode (any tag can match).
uint8 FILTER_MODE_ALL = 1 # Filter with AND mode (all tags need to match).
Expand Down
3 changes: 2 additions & 1 deletion srv/DeleteEntity.srv
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
# Remove an entity (a robot, other object) from the simulation
# Remove an entity (a robot, other object) from the simulation.
# Support for this interface is indicated through the DELETING value in GetSimulationFeatures.

string entity # Entity identified by its unique name with a namespace,
# as returned by SpawnEntity or GetEntities.
Expand Down
1 change: 1 addition & 0 deletions srv/GetEntitiesStates.srv
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
# Get objects in the scene which can be interacted, e.g. with using SetEntityState.
# Use GetEntities service instead if EntityState information for all entities is not needed.
# Support for this interface is indicated through the ENTITY_STATE_LISTING value in GetSimulationFeatures.

EntityFilters filters # Optional filters for the query, including name, category, tags,
# and overlap filters.
Expand Down
1 change: 1 addition & 0 deletions srv/GetEntityBounds.srv
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
# Get geometrical bounds for entity. This feature is available if GetSimulatorFeatures includes ENTITY_BOUNDS feature.
# Support for this interface is indicated through the ENTITY_BOUNDS value in GetSimulationFeatures.

string entity # Entity identified by its unique name as returned by GetEntities / SpawnEntity.

Expand Down
1 change: 1 addition & 0 deletions srv/GetEntityInfo.srv
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
# Get type and other information about an entity.
# Support for this interface is indicated through the ENTITY_INFO_GETTING value in GetSimulationFeatures.

string entity # Entity identified by its unique name as returned by GetEntities.

Expand Down
1 change: 1 addition & 0 deletions srv/GetEntityState.srv
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
# Get state of an entity.
# Support for this interface is indicated through the ENTITY_STATE_LISTING value in GetSimulationFeatures.

string entity # Entity identified by its unique name as returned by GetEntities / SpawnEntity.

Expand Down
1 change: 1 addition & 0 deletions srv/GetNamedPoseBounds.srv
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
# Get bounds for the named pose. This feature is available if GetSimulatorFeatures includes POSE_BOUNDS feature.
# Support for this interface is indicated through the POSE_BOUNDS value in GetSimulationFeatures.

string name # unique name (as returned from GetNamedPoses).

Expand Down
1 change: 1 addition & 0 deletions srv/GetNamedPoses.srv
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
# Get predefined poses which are convenient to for spawning, navigation goals etc.
# Support for this interface is indicated through the NAMED_POSES value in GetSimulationFeatures.

TagsFilter tags # Tags filter to apply. Only named poses with matching tags field
# will be returned. Can be empty (see TagsFilter).
Expand Down
1 change: 1 addition & 0 deletions srv/GetSimulationState.srv
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
# Gets the simulation state (paused, playing, stopped)
# Support for this interface is indicated through the SIMULATION_STATE_GETTING value in GetSimulationFeatures.

---

Expand Down
1 change: 1 addition & 0 deletions srv/GetSpawnables.srv
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
# Return a list of resources which are valid as SpawnEntity uri fields (e.g. visible to or registered in simulator).
# This interface is an optional extension and might not be implemented by your simulator, check the result_code.
# Support for this interface is indicated through the SPAWNABLES value in GetSimulationFeatures.

string[] sources # Optional field for additional sources (local or remote) to search.
# By default, each simulator has visibility of spawnables through
Expand Down
Loading