-
Notifications
You must be signed in to change notification settings - Fork 10
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 19 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,57 @@ | ||
cmake_minimum_required(VERSION 3.8) | ||
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/EntityInfo.msg" | ||
"msg/EntityState.msg" | ||
"msg/EntityWithState.msg" | ||
"msg/NamedPose.msg" | ||
"msg/PoseBounds.msg" | ||
"msg/Result.msg" | ||
"msg/SimulatorFeatures.msg" | ||
"msg/Spawnable.msg" | ||
) | ||
|
||
set(srv_files | ||
"srv/DeleteEntity.srv" | ||
"srv/GetEntities.srv" | ||
"srv/GetEntityState.srv" | ||
"srv/GetNamedPoses.srv" | ||
"srv/GetSimulatorFeatures.srv" | ||
"srv/GetSpawnables.srv" | ||
"srv/ResetSimulation.srv" | ||
"srv/SetEntityState.srv" | ||
"srv/SetSimulationPaused.srv" | ||
"srv/SpawnEntity.srv" | ||
"srv/StepSimulation.srv" | ||
) | ||
|
||
set(action_files | ||
"action/MultiStepSimulation.action" | ||
adamdbrw marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
) | ||
|
||
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. | ||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
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 not paused will return OPERATION_FAILED and error message. | ||
adamdbrw marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
|
||
--- | ||
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,14 @@ | ||||||
# Entity type and additional information | ||||||
|
||||||
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, | ||||||
# not themselves subject to validation. | ||||||
uint8 STATIC_OBJECT = 5 # Any object which is static, e.g. not supposed to change its pose | ||||||
# unless by means of SetEntityState. | ||||||
|
||||||
uint8 category # Major category for the entity. Extra entity type distinction can be made through tags. | ||||||
adamdbrw marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
uint8 category # Major category for the entity. Extra entity type distinction can be made through tags. | |
EntityCategories category # Major category for the entity. Extra entity type distinction can be made through tags. |
And the corellary change would be to have uint8 category
in the EntityCategories.msg field.
That has the downside of having to call category.category
but it keeps the data usage close to the definition. Otherwise a reader of this message only will find the datatypes if they read this message. And depending on how things are included or installed, may not have access to the other message as there's only a documentation link.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The 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 comment
The 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 comment
The 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.
I think something like that should go into the string[] tags
field or be added to EntityCategories.msg
whenever the need arises.
Maybe something like GetSupportedTags.srv
could be added to get the constants for the tags that the simulator supports.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The 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.
I could see utility for an added interface which returns tags which are currently in use. What do you think? Or I can skip the suggestion as well.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I could see utility for an added interface which returns tags which are currently in use. What do you think? Or I can skip the suggestion as well.
Adding that interface sounds good to me!
Maybe @peci1 would also like to provide their opinion here?
There was a problem hiding this comment.
Choose a reason for hiding this comment
The 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).
adamdbrw marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,8 @@ | ||
# Entity current pose, twist and acceleration | ||
|
||
std_msgs/Header header # Frame and timestamp for pose and twist. Empty frame defaults to world. | ||
adamdbrw marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
geometry_msgs/Pose pose # Pose in reference frame, ground truth. | ||
geometry_msgs/Twist twist # Ground truth body twist in the reference frame. | ||
adamdbrw marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
# It is observed and defined in the local coordinates system of the body. | ||
# 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,5 @@ | ||
# Entity with its current ground truth state. Entities are objects in the simulation such as models and links. | ||
adamdbrw marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
# Each simulator might define what an entity is in a (slightly) different way. | ||
|
||
string name # Entity unique name. | ||
EntityState state # Entity current state. |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,9 @@ | ||
# 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. | ||
PoseBounds bounds # Pose area bounds, which are empty by default, meaning pose is unbounded. | ||
adamdbrw marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
adamdbrw marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,11 @@ | ||
# Bounds for named poses, e.g. to avoid spawning with other object overlap, or parking in a spot that is too small. | ||
adamdbrw marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
# Named pose might be valid for a small object, but not suitable for a large one, or a differently shaped one. | ||
# These limits are relative to named pose or entity's top link transform, following ROS rep-103 conventions. | ||
|
||
# By default, both fields are zero vectors which means that pose is unbounded. | ||
# Otherwise, the fields are expected to form a valid box containing the (0,0,0) point which is the position. | ||
# 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. | ||
|
||
geometry_msgs/Vector3 upper_right # Optional: the upper right corner of the bounds box. | ||
adamdbrw marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
geometry_msgs/Vector3 lower_left # Optional: the lower left corner of the bounds box. |
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 deducted by last of corresponding | ||
adamdbrw marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
# 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. | ||
|
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,34 @@ | ||
# 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 (PoseBounds). | ||
uint8 SPAWNING_RESOURCE_STRING = 4 # 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 SetSimulationPaused interface | ||
adamdbrw marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
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 MultiStepSimulation action. | ||
uint8 STEP_SIMULATION_ACTION = 33 # Supports MultiStepSimulation 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
|
||
PoseBounds spawn_bounds # Optional spawn area bounds which fully encompass this object. |
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,7 @@ | ||
# Remove an entity (a robot, other object) by unique name from the simulation | ||
|
||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
||
string name # Unique name with a namespace, as returned by SpawnEntity or GetEntities. | ||
adamdbrw marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
|
||
--- | ||
|
||
Result result |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,25 @@ | ||
# Get objects in the scene which can be interacted, e.g. with using SetEntityState. | ||
|
||
string filter # Optional, defaults to empty. Return entities with matching names. | ||
adamdbrw marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
# Entity names are matched with the filter regular expression. | ||
# An empty filter will result in all entities being returned. | ||
adamdbrw marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
# Applies together with other filters (categories, tags). | ||
uint8[] categories # Optional, defaults to empty, which means no category filter. | ||
# Entities matching any of the categories will be returned. | ||
# To get entity category, use GetEntityInfo. | ||
# Applies together with other filters (filter, tags). | ||
string[] tags # Optional, defaults to empty, which means no tags filter. | ||
# Entities matching any or all of tags will be returned, depending | ||
# on tags_filter_mode. To get entity tags, use GetEntityInfo. | ||
# Applies together with other filters (filter, categories). | ||
|
||
uint8 ANY_OF = 0 # Filter with AND mode (all tags need to match). | ||
uint8 ALL_OF = 1 # Filter with OR mode (any tag can match). | ||
|
||
uint8 tags_filter_mode # Set to control filter application for tags. | ||
|
||
|
||
--- | ||
|
||
Result result | ||
EntityWithState[] entities # All entities with their states, matching the filter. |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,8 @@ | ||
# Get type and other information about an entity. | ||
|
||
string name # 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 name # 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 predefined poses which are convenient to for spawning, navigation goals etc. | ||
# This is an optional simulation feature: check status_message if you receive an empty poses vector, | ||
adamdbrw marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
# to determine whether this feature is not supported by your simulator, or named poses are simply not defined. | ||
|
||
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,6 @@ | ||
# Get a list of features supported by the simulator. | ||
# Simulators adhering to the standard need to implement at least this interface. | ||
|
||
--- | ||
|
||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
||
SimulatorFeatures features |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,16 @@ | ||
# 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. | ||
|
||
string[] sources # Optional field for additional sources (local or remote) to search. | ||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
||
# By default, each simulator has visibility of spawnables through | ||
# some mechanisms, e.g. a set of paths, registered assets etc. | ||
# Since the simulator cannot possibly look everywhere, | ||
# this field allows the user to specify additional sources. | ||
# Unrecognized values are listed as such in the result.error_message, | ||
# but do not hinder success of the response. | ||
# Sources may include subcategories and be simulator-specific. | ||
|
||
--- | ||
|
||
Result result | ||
Spawnable[] spawnables # Spawnable objects with URI and additional information. |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,16 @@ | ||
# Reset the simulation to the start, including the entire scene and the simulation time. | ||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
||
# Objects that were dynamically spawned are de-spawned. | ||
|
||
uint8 DEFAULT = 0 # same as ALL. | ||
uint8 TIME = 1 # Reset simulation time to start. | ||
uint8 STATE = 2 # Reset state such as poses and velocities. This may include state randomization | ||
# if such feature is available and turned on. | ||
uint8 SPAWNED = 4 # De-spawns all spawned entities. | ||
uint8 ALL = 7 # Fully resets simulation to the start, as if it was closed and launched again. | ||
adamdbrw marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
|
||
uint8 reset_scope # Scope of the reset. Note that simulators might only support some types of resets. | ||
adamdbrw marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
# This is a bit field which you can check for each scope e.g. reset_scope & TIME. | ||
adamdbrw marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
|
||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
||
--- | ||
|
||
Result result |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,9 @@ | ||
# Set a state of an object, which will result in an instant change in its pose and/or twist. | ||
|
||
string name # Unique name as returned by GetEntities or SpawnEntity. | ||
EntityState state # New state to set immediately. The timestamp in header is ignored. | ||
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
adamdbrw marked this conversation as resolved.
Show resolved
Hide resolved
|
||
# Note that the acceleration field may be ignored by simulators. | ||
adamdbrw marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
|
||
--- | ||
|
||
Result result |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,11 @@ | ||
# Pauses or unpauses the simulation | ||
adamdbrw marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
|
||
bool pause # If true, sets simulation state to paused, otherwise sets it to running. | ||
# If already in target state, nothing happens but the result informs about it. | ||
|
||
--- | ||
|
||
uint8 ALREADY_PAUSED = 101 # Additional result type for this call, which means simulation was already | ||
adamdbrw marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
# paused and remains so. | ||
|
||
Result result | ||
adamdbrw marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
Uh oh!
There was an error while loading. Please reload this page.