-
Notifications
You must be signed in to change notification settings - Fork 9
Proposal for simulation interfaces #1
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Changes from 26 commits
5267ea2
0cfd0fd
d874c23
10f59d2
ea23f59
97b79f7
8bae938
885a3fa
53d6ee9
aaee904
df98b24
4d551f1
95f46d9
0169e10
1e92784
9bf757f
e94797f
eabed90
271a8a1
9ec77e6
86ea8e0
9d123ed
a940c65
aee7e79
4497cbc
af3ebff
5f0aefb
5fe0d30
eb6f27e
e98721f
65a653f
4e6867d
2206c58
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,65 @@ | ||
cmake_minimum_required(VERSION 3.16) | ||
project(simulation_interfaces) | ||
|
||
if(NOT CMAKE_CXX_STANDARD) | ||
set(CMAKE_CXX_STANDARD 17) | ||
set(CMAKE_CXX_STANDARD_REQUIRED ON) | ||
endif() | ||
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") | ||
add_compile_options(-Wall -Wextra -Wpedantic) | ||
endif() | ||
|
||
find_package(ament_cmake REQUIRED) | ||
find_package(builtin_interfaces REQUIRED) | ||
find_package(geometry_msgs REQUIRED) | ||
find_package(rosidl_default_generators REQUIRED) | ||
find_package(std_msgs REQUIRED) | ||
|
||
set(msg_files | ||
"msg/Bounds.msg" | ||
"msg/EntityCategories.msg" | ||
"msg/EntityFilters.msg" | ||
"msg/EntityInfo.msg" | ||
"msg/EntityState.msg" | ||
"msg/NamedPose.msg" | ||
"msg/Result.msg" | ||
"msg/SimulationState.msg" | ||
"msg/SimulatorFeatures.msg" | ||
"msg/Spawnable.msg" | ||
"msg/TagsFilter.msg" | ||
) | ||
|
||
set(srv_files | ||
"srv/DeleteEntity.srv" | ||
"srv/GetEntities.srv" | ||
"srv/GetEntitiesStates.srv" | ||
"srv/GetEntityBounds.srv" | ||
"srv/GetEntityInfo.srv" | ||
"srv/GetEntityState.srv" | ||
"srv/GetNamedPoseBounds.srv" | ||
"srv/GetNamedPoses.srv" | ||
"srv/GetSimulationState.srv" | ||
"srv/GetSimulatorFeatures.srv" | ||
"srv/GetSpawnables.srv" | ||
"srv/ResetSimulation.srv" | ||
"srv/SetEntityState.srv" | ||
"srv/SetSimulationState.srv" | ||
"srv/SpawnEntity.srv" | ||
"srv/StepSimulation.srv" | ||
) | ||
|
||
set(action_files | ||
"action/SimulateSteps.action" | ||
) | ||
|
||
rosidl_generate_interfaces(${PROJECT_NAME} | ||
${msg_files} | ||
${srv_files} | ||
${action_files} | ||
DEPENDENCIES builtin_interfaces std_msgs geometry_msgs | ||
ADD_LINTER_TESTS | ||
) | ||
|
||
ament_export_dependencies(rosidl_default_runtime) | ||
|
||
ament_package() |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,2 +1,4 @@ | ||
# simulation_interfaces | ||
Standard interfaces for interacting with simulators from ROS 2 | ||
# Simulation Interfaces | ||
|
||
Standard ROS 2 interfaces for interacting with simulators. | ||
Messages, services, and actions are documented in their respective files. | ||
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,12 @@ | ||
# 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). | ||
|
||
uint64 steps # Action goal: step through the simulation loop this many times. | ||
--- | ||
|
||
Result result # Calling with simulation unpaused will return OPERATION_FAILED and error message. | ||
|
||
--- | ||
uint64 completed_steps # number of completed steps in this action so far. | ||
uint64 remaining_steps # number of steps remaining to be completed in this action. |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,25 @@ | ||
# Bounds which are useful in several contexts, e.g. to avoid spawning with other object overlap, | ||
# or parking in a spot that is too small. | ||
# 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. | ||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
||
|
||
# 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 area containing the (0,0,0) point which is the position. | ||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
||
# For spawning with a named pose, you should check whether the entity simulation model fits within the bounds | ||
# before calling SpawnEntity, to avoid overlaps and unstable behavior. | ||
|
||
# bounds type | ||
uint8 TYPE_EMPTY = 0 # No bounds. The points vector will be empty. | ||
uint8 TYPE_BOX = 1 # Bounding box, points field should have two values, which are | ||
# upper right and lower left corners of the box. | ||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
||
uint8 TYPE_CONVEX_HULL = 2 # Points define a convex hull (at least 3 non-collinear points). | ||
uint8 TYPE_SPHERE = 3 # A sphere with center and radius. First element of points vector is the center. | ||
# The x field of the second point of the vector is the radius (y and z are ignored). | ||
|
||
|
||
uint8 type | ||
geometry_msgs/Vector3[] points # Points defining the bounded area. Check type field to determine semantics. | ||
# Valid sizes are zero (no bounds), 2 (sphere or box, depending on type field), | ||
# and 3 or more (convex hull). |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,10 @@ | ||
# Constants for entity categories | ||
|
||
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. |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,20 @@ | ||
# A set of filters to apply to entity queries. See GetEntities, GetEntitiesStates. | ||
|
||
string filter # Optional, defaults to empty. Return entities with matching names. | ||
# Entity names are matched with the filter regular expression. | ||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
||
# An empty filter will result in all entities being returned. | ||
# The regular expression syntax is POSIX Extended, | ||
# see https://pubs.opengroup.org/onlinepubs/9799919799/ definitions. | ||
# Applies together with other filters (categories, tags). | ||
uint8[] categories # Optional, defaults to empty, which means no category filter. | ||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
||
# Entities matching any of the categories will be returned. | ||
# To get entity category, use GetEntityInfo. | ||
# Applies together with other filters (filter, tags). | ||
TagsFilter tags # Tags filter to apply. To get entity tags, use GetEntityInfo. | ||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
||
# 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. | ||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
||
|
||
Bounds bounds |
Original file line number | Diff line number | Diff line change | ||||
---|---|---|---|---|---|---|
@@ -0,0 +1,6 @@ | ||||||
# Entity type and additional information | ||||||
|
||||||
uint8 category # Major category for the entity. Extra entity type distinction can be made through tags. | ||||||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. It's a little bit awkward here, but I think that the categories should be defined in the same message as the Either we should move the enums here from EntityCategories.msg or we should move the data storage into the EntityCategories and included it as a sub-message.
Suggested change
And the corellary change would be to have That has the downside of having to call There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. The reasoning here is that if you have the constants outside, you can freely add new constants without changing message hash of the messages that use the constants. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I understand there are two different opinions here. about whether the EntityCategories message should contain the category field itself. Either solution is good with me, do you have further arguments or are there others willing to express their preference? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
I think something like that should go into the There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. @Amronos +1` on EntityCategory, I am implementing the suggestion. For GetSupportedTags, I am not sure about the semantics. Simulators I know have a flexible tag system (for example, a Tag component) which allows them to tag entities as anything both statically and dynamically. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Adding that interface sounds good to me! There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I wouldn't over-engineer this. The users will anyways need to get some external knowledge about the particular simulator they will be using. E.g. entity URIs are different for each simulator. And although there is a service that can list all spawnables, how would some automated code know what is what? If somebody wants to get a list of all supported tags, iterating through all available entities seems like a good way (although it may be a bit slowish in some implementations). |
||||||
# See EntityCategories for defined category values. | ||||||
string description # optional: verbose, human-readable description of the entity. | ||||||
string[] tags # optional: tags which are useful for filtering and categorizing entities further. |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,8 @@ | ||
# Entity current pose, twist and acceleration | ||
|
||
std_msgs/Header header # Reference frame and timestamp for pose and twist. Empty frame defaults to world. | ||
geometry_msgs/Pose pose # Pose in reference frame, ground truth. | ||
geometry_msgs/Twist twist # Ground truth linear and angular velocities | ||
# observed in the frame specified by header.frame_id | ||
# See https://github.com/ros2/common_interfaces/pull/240 for conventions. | ||
geometry_msgs/Accel acceleration # Linear and angular acceleration ground truth, following the same convention. |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,8 @@ | ||
# A named pose defined in the simulation for certain purposes such as spawning. | ||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
||
|
||
string name # Unique name. | ||
string description # Description for the user, e.g. "near the charging station". | ||
string[] tags # Optional tags which can be used to determine the named pose | ||
# purpose, for example: "spawn", "parking", "navigation_goal", | ||
# as well as fitting entity types e.g. "drone", "turtlebot3". | ||
geometry_msgs/Pose pose # Pose relative to world, which can be used with SpawnEntity.srv. |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,18 @@ | ||
# Result code and message for service calls. | ||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
||
# 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 # Result to be checked on return from service interface call | ||
string error_message # Additional error description when useful. | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. The existence of this message seems like a fundamental failing of ROS 2. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Could you elaborate? I think I understand what you mean but don't want to jump to conclusions. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. We discussed this in the PMC meeting (a few weeks ago), I do think that this You will see that many services do this pattern, which indicates to me that it should at least be a common message, but it seems very likely that this could be built into the underlying service mechanism. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. @mjcarroll That seems very reasonable to me. How do I proceed with the standard? Since the message is clearly not there yet, I can't make a functional message package without including the Result message. Should I keep it in and then before the standard is implemented we would seek to reuse the common message? Or in case it is implemented into the service mechanism, remove it? I would imagine such implementation won't make it into the next release though. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. For now, I included a readme section. |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,16 @@ | ||
# Simulation states used in SetSimulationState and returned in GetSimulationState | ||
|
||
uint8 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. | ||
# 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. | ||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
||
|
||
uint8 state |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,37 @@ | ||
# 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. | ||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
||
uint8 SPAWNING_RESOURCE_STRING = 7 # Supports SpawnEntity resource_string field. | ||
|
||
uint8 ENTITY_STATE_LISTING = 10 # Supports GetEntityState interface. | ||
uint8 ENTITY_STATE_SETTING = 11 # Supports SetEntityState 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_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. | ||
|
||
|
||
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) | ||
# * urdf (Unified Robot Description Format) | ||
# * usd (Universal Scene Description) | ||
# * mjcf (MuJoCo's XML format) | ||
# or whatever simulator-native formats that are supported. | ||
string[] spawn_formats | ||
string custom_info # Optional: extra information for the caller, which could point to | ||
# documentation, version compatibility and other useful meta information. |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,5 @@ | ||
# Robot or other object which can be spawned in simulation runtime. | ||
|
||
string uri # URI which will be accepted by SpawnEntity service. | ||
string description # Optional description for the user, e.g. "robot X with sensors A,B,C". | ||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
||
Bounds spawn_bounds # Optional spawn area bounds which fully encompass this object. |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,10 @@ | ||
# 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. | ||
|
||
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). | ||
|
||
uint8 filter_mode # Set to control filter application for tags. |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,28 @@ | ||
<?xml version="1.0"?> | ||
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?> | ||
<package format="3"> | ||
<name>simulation_interfaces</name> | ||
<version>1.0.0</version> | ||
<description>A package containing simulation interfaces including messages, services and actions</description> | ||
<maintainer email="[email protected]">Adam Dabrowski</maintainer> | ||
<license>Apache License 2.0</license> | ||
<url type="repository">https://github.com/ros-simulation/simulation-interfaces</url> | ||
<author email="[email protected]">Adam Dabrowski</author> | ||
|
||
<buildtool_depend>ament_cmake</buildtool_depend> | ||
<buildtool_depend>rosidl_default_generators</buildtool_depend> | ||
|
||
<depend>builtin_interfaces</depend> | ||
<depend>geometry_msgs</depend> | ||
<depend>std_msgs</depend> | ||
|
||
<exec_depend>rosidl_default_runtime</exec_depend> | ||
|
||
<test_depend>ament_lint_common</test_depend> | ||
|
||
<member_of_group>rosidl_interface_packages</member_of_group> | ||
|
||
<export> | ||
<build_type>ament_cmake</build_type> | ||
</export> | ||
</package> |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,8 @@ | ||
# Remove an entity (a robot, other object) from the simulation | ||
|
||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
||
string entity # Entity identified by its unique name with a namespace, | ||
# as returned by SpawnEntity or GetEntities. | ||
|
||
--- | ||
|
||
Result result |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,11 @@ | ||
# Get objects in the scene which can be interacted with, e.g. with using SetEntityState. | ||
# You can get further information about entities through GetEntityInfo and GetEntityState services. | ||
# There is also a GetEntitiesStates service if you would like to get state for each entity. | ||
|
||
EntityFilters filters # Optional filters for the query, including name, category, tags, | ||
# and overlap filters. | ||
|
||
--- | ||
|
||
Result result | ||
Entity[] entities # All entities matching the filters. |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,11 @@ | ||
# 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. | ||
|
||
EntityFilters filters # Optional filters for the query, including name, category, tags, | ||
# and overlap filters. | ||
|
||
--- | ||
|
||
Result result | ||
Entity[] entities # All entities matching the filters. | ||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
||
EntityState[] states # States for these entities. |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,10 @@ | ||
# Get geometrical bounds for entity. This feature is available if GetSimulatorFeatures includes ENTITY_BOUNDS feature. | ||
|
||
string entity # Entity identified by its unique name as returned by GetEntities / SpawnEntity. | ||
|
||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
||
--- | ||
|
||
Result result | ||
Bounds bounds # Entity bounds. Only valid if result.result_code is OK. | ||
# Bounds with TYPE_BOX should be returned, unless there is a configuration | ||
# parameter for the simulator to control the type and it is set otherwise. |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,8 @@ | ||
# Get type and other information about an entity. | ||
|
||
string entity # Entity identified by its unique name as returned by GetEntities / SpawnEntity. | ||
|
||
--- | ||
|
||
Result result | ||
EntityInfo info # Only valid if result.result_code is OK. |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,8 @@ | ||
# Get state of an entity. | ||
|
||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
||
string entity # Entity identified by its unique name as returned by GetEntities / SpawnEntity. | ||
|
||
--- | ||
|
||
Result result | ||
EntityState state # Entity ground truth state. Valid when result.result = OK. |
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,8 @@ | ||
# Get bounds for the named pose. This feature is available if GetSimulatorFeatures includes POSE_BOUNDS feature. | ||
|
||
string name # unique names (as returned from GetNamedPoses). | ||
|
||
--- | ||
|
||
Result result | ||
Bounds bounds # bounds for the named pose. |
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,9 @@ | ||
# Get predefined poses which are convenient to for spawning, navigation goals etc. | ||
|
||
TagsFilter tags # Tags filter to apply. Only named poses with matching tags field | ||
# will be returned. Can be empty (see TagsFilter). | ||
|
||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
||
--- | ||
|
||
Result result | ||
NamedPose[] poses # A list of predefined poses, which may be empty. |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,7 @@ | ||
# Gets the simulation state (paused, playing, stopped) | ||
|
||
--- | ||
|
||
SimulationState state # Current state of the simulation. | ||
|
||
Result result |
Uh oh!
There was an error while loading. Please reload this page.