Skip to content

Commit 86d4cce

Browse files
adamdbrwpeci1scpetersDLuazeey
authored
Proposal for simulation interfaces (#1)
Following ros-infrastructure/rep#410, this PR contains a first version of simulation interfaces. Signed-off-by: Adam Dąbrowski <[email protected]> Co-authored-by: Martin Pecka <[email protected]> Co-authored-by: Steve Peters <[email protected]> Co-authored-by: David V. Lu!! <[email protected]> Co-authored-by: Addisu Z. Taddese <[email protected]> Co-authored-by: Tully Foote <[email protected]> Co-authored-by: Sebastian Castro <[email protected]> Co-authored-by: Michał Pełka <[email protected]> Co-authored-by: Paweł Liberadzki <[email protected]>
1 parent c229347 commit 86d4cce

32 files changed

+538
-2
lines changed

CMakeLists.txt

Lines changed: 66 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,66 @@
1+
cmake_minimum_required(VERSION 3.16)
2+
project(simulation_interfaces)
3+
4+
if(NOT CMAKE_CXX_STANDARD)
5+
set(CMAKE_CXX_STANDARD 17)
6+
set(CMAKE_CXX_STANDARD_REQUIRED ON)
7+
endif()
8+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
9+
add_compile_options(-Wall -Wextra -Wpedantic)
10+
endif()
11+
12+
find_package(ament_cmake REQUIRED)
13+
find_package(builtin_interfaces REQUIRED)
14+
find_package(geometry_msgs REQUIRED)
15+
find_package(rosidl_default_generators REQUIRED)
16+
find_package(std_msgs REQUIRED)
17+
18+
set(msg_files
19+
"msg/Bounds.msg"
20+
"msg/EntityCategory.msg"
21+
"msg/EntityFilters.msg"
22+
"msg/EntityInfo.msg"
23+
"msg/EntityState.msg"
24+
"msg/NamedPose.msg"
25+
"msg/Result.msg"
26+
"msg/SimulationState.msg"
27+
"msg/SimulatorFeatures.msg"
28+
"msg/Spawnable.msg"
29+
"msg/TagsFilter.msg"
30+
)
31+
32+
set(srv_files
33+
"srv/DeleteEntity.srv"
34+
"srv/GetEntities.srv"
35+
"srv/GetEntitiesStates.srv"
36+
"srv/GetEntityBounds.srv"
37+
"srv/GetEntityInfo.srv"
38+
"srv/GetEntityState.srv"
39+
"srv/GetNamedPoseBounds.srv"
40+
"srv/GetNamedPoses.srv"
41+
"srv/GetSimulationState.srv"
42+
"srv/GetSimulatorFeatures.srv"
43+
"srv/GetSpawnables.srv"
44+
"srv/ResetSimulation.srv"
45+
"srv/SetEntityInfo.srv"
46+
"srv/SetEntityState.srv"
47+
"srv/SetSimulationState.srv"
48+
"srv/SpawnEntity.srv"
49+
"srv/StepSimulation.srv"
50+
)
51+
52+
set(action_files
53+
"action/SimulateSteps.action"
54+
)
55+
56+
rosidl_generate_interfaces(${PROJECT_NAME}
57+
${msg_files}
58+
${srv_files}
59+
${action_files}
60+
DEPENDENCIES builtin_interfaces std_msgs geometry_msgs
61+
ADD_LINTER_TESTS
62+
)
63+
64+
ament_export_dependencies(rosidl_default_runtime)
65+
66+
ament_package()

README.md

Lines changed: 25 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,2 +1,25 @@
1-
# simulation_interfaces
2-
Standard interfaces for interacting with simulators from ROS 2
1+
# Simulation Interfaces
2+
3+
Standard ROS 2 interfaces for interacting with simulators.
4+
Messages, services, and actions are documented in their respective files.
5+
6+
## Result.msg
7+
8+
The standard includes a generic message for handling service responses, [Result.msg](msg/Result.msg),
9+
which will likely not be included in the final version of the standard. Since it is generic, it will either be promoted to a common message or included in the
10+
service mechanism itself.
11+
12+
## Suggested interface implementation priorities
13+
14+
[GetSimulatorFeatures](msg/GetSimulationFeatures.msg) should be implemented first, as it provides users with information about
15+
the state of support for all standard simulation interfaces.
16+
17+
Following that, aim for maintaining consistency within the implemented feature, such as enabling both
18+
_Get_ and _Set_ parts.
19+
20+
Some interfaces represent optional utility and are considered lower priority:
21+
- [GetEntityBounds](srv/GetEntityBounds.srv)
22+
- [GetNamedPoseBounds](srv/GetNamedPoseBounds.srv)
23+
- [GetNamedPoses](srv/GetNamedPoses.srv)
24+
- [GetSpawnables](srv/GetSpawnables.srv)
25+
- [SetEntityInfo](srv/SetEntityInfo.srv)

action/SimulateSteps.action

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,13 @@
1+
# Assuming the simulation is paused, simulate a finite number of steps and return to paused state.
2+
# The action returns feedback after each complete step.
3+
# For a service alternative, see StepSimulation, which often makes more sense when doing a single step (steps = 1).
4+
# Support for this interface is indicated through the STEP_SIMULATION_ACTION value in GetSimulationFeatures.
5+
6+
uint64 steps # Action goal: step through the simulation loop this many times.
7+
---
8+
9+
Result result # Calling with simulation unpaused will return OPERATION_FAILED and error message.
10+
11+
---
12+
uint64 completed_steps # number of completed steps in this action so far.
13+
uint64 remaining_steps # number of steps remaining to be completed in this action.

msg/Bounds.msg

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
1+
# Bounds which are useful in several contexts, e.g. to avoid spawning with other object overlap,
2+
# or parking in a spot that is too small.
3+
# Certain goals or points might be valid for a small object, but not suitable for a large one,
4+
# or a differently shaped one.
5+
# Bounds can be also checked to ensure certain scenario conditions are met.
6+
# For entities, these limits are relative to entity's canonical link transform, following ROS rep-103 convention.
7+
8+
# As bounds are optional in most interfaces, TYPE_EMPTY signifies empty bounds, to be understood as "unbounded".
9+
# Otherwise, the fields are expected to define a valid volume.
10+
# For spawning with a named pose, you should check whether the entity simulation model fits within the bounds
11+
# before calling SpawnEntity, to avoid overlaps and unstable behavior.
12+
13+
# bounds type
14+
uint8 TYPE_EMPTY = 0 # No bounds. The points vector will be empty.
15+
uint8 TYPE_BOX = 1 # Axis-aligned bounding box, points field should have two values,
16+
# which are upper right and lower left corners of the box.
17+
uint8 TYPE_CONVEX_HULL = 2 # Points define a convex hull (at least 3 non-collinear points).
18+
uint8 TYPE_SPHERE = 3 # A sphere with center and radius. First element of points vector is the center.
19+
# The x field of the second point of the vector is the radius (y and z are ignored).
20+
21+
22+
uint8 type
23+
geometry_msgs/Vector3[] points # Points defining the bounded area. Check type field to determine semantics.
24+
# Valid sizes are zero (no bounds), 2 (sphere or box, depending on type field),
25+
# and 3 or more (convex hull).

msg/EntityCategory.msg

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,16 @@
1+
# Entity major category, which often warrants a specific way to handle such entity, e.g. when handling humans
2+
# or mapping persistence for dynamic vs static objects.
3+
4+
uint8 CATEGORY_OBJECT = 0 # Generic or unspecified type.
5+
uint8 CATEGORY_ROBOT = 1 # A broad category for mobile robots, arms, drones etc.,
6+
# usually with ROS 2 interfaces.
7+
uint8 CATEGORY_HUMAN = 2 # Simulated humans, e.g. pedestrians, warehouse workers.
8+
# Compared to CATEGORY_DYNAMIC_OBJECT, humans are often expected to be treated
9+
# exceptionally in regards to safety constraints.
10+
uint8 CATEGORY_DYNAMIC_OBJECT = 4 # Vehicles, animals, mobile obstacles, typically to present a detection and
11+
# tracking challenge, such as when simulation is used to test robot perception
12+
# or navigation stack.
13+
uint8 CATEGORY_STATIC_OBJECT = 5 # Any object which is static, e.g. not supposed to change its pose
14+
# unless by means of SetEntityState.
15+
16+
uint8 category

msg/EntityFilters.msg

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
1+
# A set of filters to apply to entity queries. See GetEntities, GetEntitiesStates.
2+
3+
string filter # Optional, defaults to empty. Return entities with matching names.
4+
# Entity names are matched with the filter regular expression.
5+
# An empty filter will result in all entities being returned.
6+
# The regular expression syntax is POSIX Extended,
7+
# see https://pubs.opengroup.org/onlinepubs/9799919799/ definitions.
8+
# Applies together with other filters (categories, tags).
9+
EntityCategory[] categories # Optional, defaults to empty, which means no category filter.
10+
# Entities matching any of the categories will be returned.
11+
# To get entity category, use GetEntityInfo.
12+
# Applies together with other filters (filter, tags).
13+
# Check ENTITY_CATEGORIES in GetSimulatorFeatures to determine if
14+
# your simulator supports entity categories.
15+
TagsFilter tags # Tags filter to apply. To get entity tags, use GetEntityInfo.
16+
# Applies together with other filters (filter, categories).
17+
# Check support for this feature (ENTITY_TAGS) in GetSimulationFeatures.
18+
Bounds bounds # if bounds are not empty, the overlap filter is applied
19+
# and entities overlapping with bounds will be returned.
20+
# Note that not all bound types might be supported by the simulator,
21+
# though at least TYPE_SPHERE needs to be supported.
22+
# Check ENTITY_BOUNDS_BOX and ENTITY_BOUNDS_CONVEX in GetSimulationFeatures
23+
# to determine whether your simulator supports other bound types.
24+
# If service is called with filter bounds set to an unsupported type,
25+
# a FEATURE_UNSUPPORTED result will be returned.

msg/EntityInfo.msg

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
# Entity type and additional information
2+
3+
EntityCategory category # Major category for the entity. Extra entity type distinction can be made through tags.
4+
string description # optional: verbose, human-readable description of the entity.
5+
string[] tags # optional: tags which are useful for filtering and categorizing entities further.

msg/EntityState.msg

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
# Entity current pose, twist and acceleration
2+
3+
std_msgs/Header header # Reference frame and timestamp for pose and twist. Empty frame defaults to world.
4+
geometry_msgs/Pose pose # Pose in reference frame, ground truth.
5+
geometry_msgs/Twist twist # Ground truth linear and angular velocities
6+
# observed in the frame specified by header.frame_id
7+
# See https://github.com/ros2/common_interfaces/pull/240 for conventions.
8+
geometry_msgs/Accel acceleration # Linear and angular acceleration ground truth, following the same convention.

msg/NamedPose.msg

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
# A named pose defined in the simulation for certain purposes such as spawning.
2+
3+
string name # Unique name.
4+
string description # Description for the user, e.g. "near the charging station".
5+
string[] tags # Optional tags which can be used to determine the named pose
6+
# purpose, for example: "spawn", "parking", "navigation_goal",
7+
# as well as fitting entity types e.g. "drone", "turtlebot3".
8+
geometry_msgs/Pose pose # Pose relative to world, which can be used with SpawnEntity.srv.

msg/Result.msg

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,18 @@
1+
# Result code and message for service calls.
2+
# Note that additional results for specific services can defined within them using values above 100.
3+
4+
uint8 RESULT_FEATURE_UNSUPPORTED = 0 # Feature is not supported by the simulator, check GetSimulatorFeatures.
5+
# While feature support can sometimes be deduced from presence of corresponding
6+
# service / action interface, in other cases it is about supporting certain
7+
# call parameters, formats and options within interface call.
8+
uint8 RESULT_OK = 1
9+
uint8 RESULT_NOT_FOUND = 2 # No match for input (such as when entity name does not exist).
10+
uint8 RESULT_INCORRECT_STATE = 3 # Simulator is in an incorrect state for this interface call, e.g. a service
11+
# requires paused state but the simulator is not paused.
12+
uint8 RESULT_OPERATION_FAILED = 4 # Request could not be completed successfully even though feature is supported
13+
# and the input is correct; check error_message for details.
14+
# Implementation rule: check extended codes for called service
15+
# (e.g. SpawnEntity) to provide a return code which is more specific.
16+
17+
uint8 result # Result to be checked on return from service interface call
18+
string error_message # Additional error description when useful.

0 commit comments

Comments
 (0)