Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
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
128 changes: 125 additions & 3 deletions rep.md
Original file line number Diff line number Diff line change
Expand Up @@ -19,10 +19,11 @@ This REP defines a standard schema and strict profile of OpenUSD (Universal Scen
2. **Runtime integrations** (ROS Interfaces).
3. **Converters and web visualization** (especially glTF 2.0 conversion).

To achieve this, the specification addresses three key areas:
To achieve this, the specification addresses four key areas:
* **Section 1** adopts existing upstream standards and recommendations (AOUSD, ASWF, NVIDIA) to establish a baseline for correct simulation assets.
* **Section 2** defines novel, declarative API schemas for ROS interfaces to ensure engine-agnostic runtime behavior.
* **Section 3** defines a strict interoperability profile to support export pathways to other formats, ensuring compatibility with standards like glTF 2.0.
* **Section 4** defines schemas for robot control, covering both low-level joint identification and high-level application-level controllers.

## Motivation

Expand Down Expand Up @@ -176,7 +177,7 @@ The root prim of a ROS-interfaced simulation asset may define its context namesp

ROS interface schemas (`RosTopicAPI`, `RosServiceAPI`, `RosActionAPI`) must be applied to prims according to these placement rules:

* **Robot-wide interfaces:** Aggregate interfaces spanning a kinematic tree (e.g., `JointState` publisher, `FollowJointTrajectory` server) must be placed on or directly beneath the prim bearing the `RosContextAPI`.
* **Robot-wide interfaces:** Aggregate interfaces spanning a kinematic tree (e.g., `JointState` publisher, `FollowJointTrajectory` server) should be placed at root prim of the robot assembly.
* **Sensor interfaces:** Localized interfaces (e.g., `Image`, `LaserScan`) must be placed on a child `UsdGeomXform` of the physical link. Multiple interfaces for the same sensor (e.g., `image_raw` and `camera_info`) must distribute them across separate child prims, one interface per prim.
* **Interface prims must reside outside payloads.** Prims bearing `Ros*API` schemas are part of the lightweight kinematic/interface graph and must be traversable without loading geometry payloads.

Expand Down Expand Up @@ -234,7 +235,12 @@ Note: The broadcast frequency of TF frames is an implementation detail left to t
### 2.8 Optical Frames
OpenUSD cameras natively face the -Z axis, whereas ROS optical frames (REP 103) must face +Z. To bridge this without opaque simulator-side rotations, authors must decouple the physical sensor from its optical interface. Authors must create a child UsdGeomXform (e.g., `camera_optical_frame`) rotated 180 degrees around its local X-axis. All RosTopicAPI and RosFrameAPI schemas must be applied exclusively to this optical frame, ensuring deterministic data orientation in RViz.

---
### 2.9 Custom names to ROS joints.

Number of concepts in ROS (e.g. robot descriptions, controllers) relly on joints names.
To ensure that joints are correctly identified and mapped to said concepts, the custom property `ros:joint:name` must be applied to all Prims bearing built-in`UsdPhysicsJoint` schema.
This string value is source of joint name for all ROS communications (e.g., `FollowJointTrajectory` action goals, `JointState` messages), intergration with ROS tools (e.g., `ros2_control`), and mapping to other formats (e.g., MJCF's `<joint name="">`).
If this property is missing, simulators must fall back to using the prim name.

## 3. Export and Conversion

Expand Down Expand Up @@ -288,6 +294,122 @@ OpenUSD and robotics XML formats (URDF, SDF, MJCF) are fundamentally mismatched
* **API Translation:** Ros*API schemas must map exclusively to modern extension blocks (e.g., SDF `<plugin>`, MJCF `<extension>`). Obsolete approaches such as injecting legacy `<gazebo>` tags into URDF are not allowed.
* **Discard, not inject:** OpenUSD-native metadata (layer stacks, unselected variants) must be cleanly discarded. Injecting custom, non-standard XML elements to store unmappable OpenUSD states is not recommended. If pipeline necessitates it for practicality, such metadata must be confined to valid, format-native extension points.

## 4. Robot Control

In robotic simulation there are two approaches to simulating a robotic system — application level and control level simulation.

In control level simulation, the focus is on the individual components.
This approach is to be used for advanced use cases or validating low level robot controllers.
In this case the simulator is to expose joint state and command interface to control algorithm using API.
Good example of such API is `hardware_interface` in `ros2_control` package.
The REP-XXXX does not propose shape of the API and interface, and simulators are to build and maintain compatibility with external control frameworks,
it can be both ROS communication, inter-process communication, a shared library loaded by a simulator process or hardware-in-the loop solution (e.g. CAN bus link).

In application level simulation, the simulator simulates the robot as a whole, including its physical properties, kinematics, and dynamics.
This approach is meant to be used for application testing (e.g. whole robotics stacks, mapping, localization frameworks).
In this approach the controller is integrated in the simulator codebase and managed by parameters of the prim and ROS communication.

### 4.1 External Control Interfaces

The ROS 2 external control `ROSExternalControlAPI` is a schema for exposing robot control interfaces to external control algorithms.
This schema is to be included as a built-in schema via `prepend apiSchemas` by a simulator-specific interface for controller.
Simulator loading prim with this schema should establish connection, load controller plugin, spawn a controller instance or set up hardware-in-the-loop connection to the robot controller,
and expose the control and state interfaces to control entity.

### 4.2 Integrated Controller Simulation

`ROSIntegratedControlAPI` allows instantiating robot controllers directly in the simulated scene.
It must reference one or more prims that have [ROSTopicAPI](#24-topic-interface-rostopicapi), [ROSServiceAPI](#25-service-interface-rosserviceapi) or [ROSActionAPI](#26-action-interface-rosactionapi).
This schema is to be included as a built-in schema via `prepend apiSchemas` by a simulator-specific controller schema in the simulator.
Example can be `simulatorXYZ::CustomROSRigidBodyTwistControllerAPI` which will include as built-in `ROSControlAPI` and reference prims:
- `ROSTopicAPI` for subscription of control message.
- `PhysicsRigidBodyAPI` for interaction with the physics engine.

USD does not enforce API schema constraints on referenced prims at the schema definition level. It is the responsibility of the simulator to validate that all prims referenced by ROSControlAPI have at least one of the following API schemas applied: `ROSTopicAPI`, `ROSServiceAPI` or `ROSActionAPI`.

### 4.2.1 Built-in Controllers

The following schemas are built-in controller schemas that include
`ROSControlAPI` as a built-in via `prepend apiSchemas`.
Simulators may implement these schemas to provide a standardized
control interface for common use cases.
The following controllers are proposed as minimal for initial compliance.
The parameters and logic should follow established controllers in the ROS ecosystem and allow bootstrapping robot simulation with minimal custom development against
the typical use cases.
Simulators may choose to implement additional controllers as needed for their specific use cases and robot types, but these three are proposed as a baseline for compliance for
application level simulation.
The implementation should allow performing multi-robot simulation and control by leveraging the namespaces.

#### 4.2.1.1 ROSRigidBodyTwistControllerAPI

Controls a rigid body by subscribing to a topic with type `geometry_msgs/Twist`
and applying the commanded linear and angular velocities directly to the robot's body
with optional acceleration and velocity limits.
Implementation should follow logic similar to the `diff_drive_controller` in `ros2_controllers` package.

- `rel ros:rigid_body_twist:subscriber`: Reference to a prim with `ROSTopicAPI`
for subscribing to twist control messages.
- `rel ros:rigid_body_twist:body`: Reference to a prim with
`UsdPhysicsRigidBodyAPI` for applying velocities.

- `double ros:rigid_body_twist:cmd_vel_timeout`: Timeout in seconds after
which the command is considered stale. Default: `0.5`.
- `double ros:rigid_body_twist:linear:x:max_velocity`: Maximum linear velocity in m/s.
- `double ros:rigid_body_twist:linear:x:max_acceleration`: Maximum linear acceleration in m/s².
- `double ros:rigid_body_twist:angular:z:max_velocity`: Maximum angular velocity in rad/s.
- `double ros:rigid_body_twist:angular:z:max_acceleration`: Maximum angular acceleration in rad/s².

#### 4.2.1.2 ROSDiffDriveControllerAPI

Controls a differential drive robot by subscribing to a topic with type
`geometry_msgs/Twist` message and converting the commanded linear
and angular velocities into individual wheel velocities applied
to the simulator joints.
The computed velocities should be applied to prims with `UsdPhysicsDriveAPI` (part of the native `USDPhysics`) representing the wheel joints,
and the controller should publish odometry data to a topic with type `nav_msgs/Odometry`.
Implementation should follow logic similar to the `diff_drive_controller` in `ros2_controllers` package.

- `rel ros:diff_drive:subscriber`: Reference to prim with `ROSTopicAPI` for subscribing to velocity commands.
- `rel ros:diff_drive:odom`: Reference to prim with `ROSTopicAPI` for publishing odometry data.
- `rel[] ros:diff_drive:left_wheels`: References to prims with `UsdPhysicsDriveAPI` representing left wheel joints.
- `rel[] ros:diff_drive:right_wheels`: References to prims with `UsdPhysicsDriveAPI` representing right wheel joints.
- `double ros:diff_drive:wheel_separation`: Distance between left and right wheels in meters.
- `double ros:diff_drive:wheel_radius`: Radius of the wheels in meters.
- `double ros:diff_drive:cmd_vel_timeout`: Timeout in seconds after which the command is considered stale. Default: `0.5`.
- `double ros:diff_drive:linear:x:max_velocity`: Maximum linear velocity in m/s.
- `double ros:diff_drive:linear:x:max_acceleration`: Maximum linear acceleration in m/s².
- `double ros:diff_drive:angular:z:max_velocity`: Maximum angular velocity in rad/s.
- `double ros:diff_drive:angular:z:max_acceleration`: Maximum angular acceleration in rad/s².

#### 4.2.1.3 ROSJointTrajectoryControllerAPI

Executes a joint trajectory by accepting a `control_msgs/FollowJointTrajectory` action goal and commanding
the simulator to follow the specified trajectory.
Implementation should follow logic similar to the `joint_trajectory_controller` in `ros2_controllers` package.
Implementation needs to check the name for [custom joint names](rep.md#29-custom-names-to-ros-joints) in `ros:joint:name` property of the joint prims and
use it for mapping trajectory points to joints in the simulator.

- `rel ros:joint_trajectory:server`: Reference to a prim with `ROSActionAPI`
for receiving trajectory action goals.
- `rel[] ros:joint_trajectory:command_joints`: References to prims with `UsdPhysicsJointAPI`.
- `double ros:joint_trajectory:action_monitor_rate`: Frequency in Hz for
monitoring trajectory execution progress.
- `double ros:joint_trajectory:stopped_velocity_tolerance`: Velocity tolerance
at the end of the trajectory that indicates the controlled system has stopped.
- `double ros:joint_trajectory:timeout`: Maximum time allowed to reach the trajectory goal.

#### 4.2.1.4 ROSJointStateBroadcasterAPI

Reads joint states from the simulator and publishes them as `sensor_msgs/JointState` messages to a ROS topic.
Implementation should follow logic similar to the `joint_state_broadcaster` in `ros2_controllers` package.
Implementation needs to check the name for [custom joint names](rep.md#29-custom-names-to-ros-joints) in `ros:joint:name`
property of the joint prims and use it for mapping trajectory points to joints in the simulator.

- `rel ros:joint_state_broadcaster:publisher`: Reference to a prim with `ROSTopicAPI` for publishing joint state data.
- `rel[] ros:joint_state_broadcaster:joints`: References to prims with `UsdPhysicsJointAPI` representing the joints whose states are to be broadcast.
- `double ros:joint_state_broadcaster:publish_rate`: Frequency in Hz at which joint states are published.
- `string ros:joint_state_broadcaster:frame_id`: The TF frame ID to be used in the published JointState messages.

## Tools

### Schema Definition
Expand Down
Loading