From 6b5ba1a68ed86a8373f3212df1d9a5abfd497cd4 Mon Sep 17 00:00:00 2001 From: Adam Dabrowski Date: Thu, 19 Mar 2026 15:06:24 +0100 Subject: [PATCH 001/111] draft Signed-off-by: Adam Dabrowski --- rep.md | 225 +++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 225 insertions(+) create mode 100644 rep.md diff --git a/rep.md b/rep.md new file mode 100644 index 0000000..34733e7 --- /dev/null +++ b/rep.md @@ -0,0 +1,225 @@ +# REP 2040 -- OpenUSD Conventions for Simulation Asset Interoperability + +| Field | Value | +| :--- | :--- | +| **REP** | 2040 | +| **Title** | OpenUSD Conventions for Simulation Asset Interoperability | +| **Author** | Adam Dabrowski, Mateusz Zak (Robotec.ai) | +| **Status** | Draft | +| **Type** | Standards Track | +| **Content-Type** | text/markdown | +| **Created** | 2026-03-03 | +| **Requires** | REP 103, REP 105, OpenUSD Core Spec v1.0.1 | + +## Abstract + +This REP defines a standard schema and strict profile of OpenUSD (Universal Scene Description) for the interchange of robotics simulation assets. The scope includes robots, sensors, static environments (e.g., warehouse racks), and dynamic props. This REP aims to ensure that a single asset functions consistently across: + +1. **Simulation and physics engines** (Gazebo, Isaac Sim, MuJoCo, O3DE). +2. **Runtime integrations** (ROS 2 Interfaces). +3. **Converters and web visualization** (especially glTF 2.0 conversion). + +To achieve this, the specification is divided into three distinct logical areas: +* **Section 1** ratifies 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 2 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. + +## Specification + +The keywords "must", "must not", "required", "shall", "shall not", "should", "should not", "recommended", "may", and "optional" in this document are to be interpreted as described in RFC 2119. + +--- + +## 1. Simulation Assets Baseline + +This section confirms and standardizes prior work and recommendations for OpenUSD simulation assets. It draws from the Alliance for OpenUSD (AOUSD), the ASWF USD Working Group, and NVIDIA Asset Requirements. *Note: As AOUSD domain-specific working groups formalize physics and robotics specifications, recommendations in this section are subject to evolution and alignment.* + +### 1.1 Coordinate Systems & Units +To ensure alignment with ROS standards (REP 103) and stability across solvers: + +* **Units:** All linear dimensions in the USD stage must be defined in meters, and all mass values in kilograms. + * `metersPerUnit` and `kilogramsPerUnit` metadata must be set to `1.0` in the root layer. + * Simulators importing these assets must apply this scaling factor to all derived physical quantities (torque, stiffness, inertia) at runtime. +* **Up-Axis & Chirality:** The stage `upAxis` must be set to `"Z"` and follow the Right-Hand Rule. +* **Root Transforms:** Assets must not rely on root-node rotations (e.g., `xformOp:rotateX = -90`) to align geometry. Points and normals should be transform-applied (frozen) to Z-up at the source level. +* **Asset Pivots:** For assets intended to be placed on the ground (e.g., warehouse racks), the root origin should be located at the bottom-center of the asset bounding box (Z=0) to facilitate predictable drag-and-drop scene composition in simulators. Mobile bases should adhere to REP 105 origin conventions. + +### 1.2 Asset Structure & Composition +This REP adopts the ASWF Guidelines for Structuring USD Assets. + +#### 1.2.1 The Composition Model +* **Components:** Atomic assets (e.g., a `LidarSensor`, a `Box`) must have `kind="component"` on their root prim. +* **Assemblies:** Aggregates (e.g., a `Warehouse` containing racks) must have `kind="assembly"` or `kind="group"`. +* A `component` must not contain another `component`, allowing converters to easily identify the "atomic units" of the scene. + +#### 1.2.2 Composition Arcs (LIVERPS Constraints) +To guarantee that simulation assets remain self-contained, portable, and predictable across different simulator parsers, asset authors must adhere to the following constraints regarding OpenUSD's LIVERPS composition arcs: +* **[L] Local:** Primary authoring of overrides and properties on the asset is fully supported. +* **[I] Inherits & [S] Specializes:** Asset authors should not rely on `Inherits` or `Specializes` arcs for core robot kinematics, physics APIs, or ROS schemas when distributing standalone assets. These arcs create hard dependencies on external class hierarchies; if a simulator's environment lacks the base class definitions, the asset will fail to parse correctly. +* **[V] VariantSets:** Permitted and encouraged for asset reusability (see Section 1.2.3). +* **[R] References:** Permitted for logical assembly (e.g., composing a robot by referencing an independent `arm.usd` and `base.usd`). +* **[P] Payloads (The Payload Pattern):** Heavy data (high-resolution meshes, point clouds, large textures) must be referenced via Payloads rather than standard References. + * Payloads must not gate joint or link prims themselves. The kinematic topology (Prims bearing `PhysicsRigidBodyAPI`, `PhysicsJoint` schemas, and `Ros2*API` schemas) must reside in the primarily loaded scene graph (e.g., via Local authoring or standard References). + * The Payload should solely encapsulate the nested geometric and material data. This enables ROS parsers and web converters to traverse the lightweight kinematic tree efficiently without loading heavy buffers. + +#### 1.2.3 Variants and Reusability +OpenUSD `VariantSets` are the normative mechanism for asset reusability (e.g., encapsulating multiple furniture styles, different robot end-effectors, or optional sensor suites within a single asset). +* **Default Variant Fallback:** Any asset utilizing `VariantSets` must author a default variant selection. This ensures that if the asset is loaded by a simulator or CI/CD pipeline without explicit variant overrides, it resolves to a valid, predictable physical and visual state. +* **ROS Interface Resolution:** A change in a variant selection may add or remove Prims containing `Ros2*API` schemas (e.g., swapping a generic robot head for a sensor-equipped head). Simulators and tooling must only evaluate and spawn ROS interfaces that are active within the currently resolved variant state of the stage. + +#### 1.2.4 Asset Management & FileFormat Plugins +* **Path Resolution:** Internal references must use relative paths (`./geo/mesh.usdc`). External dependencies to other ROS packages must use the `package://` URI scheme. Absolute paths and proprietary schemes (e.g., `omniverse://`) are prohibited in distributed assets. +* **Native Composition vs. Custom Prefabs:** The use of custom or vendor-specific string attributes (e.g., `custom string my_sim:prefabPath = "robot.usd"`) to dynamically load, instantiate, or compose assets at runtime is strictly prohibited for interoperable assets. Asset composition must rely purely on native OpenUSD references or payloads. +* **FileFormat Plugins:** OpenUSD supports FileFormat plugins (e.g., MuJoCo's `usdMjcf` plugin) to dynamically translate legacy formats into USD stages at runtime. While these plugins are recommended for import pathways, this REP governs the *resulting in-memory OpenUSD data*. Plugins interfacing with the ROS 2 ecosystem must generate stages that conform to the physical hierarchies and API schemas defined in this document. + +#### 1.2.5 ROS-Compatible Identifiers +OpenUSD allows flexible naming, but ROS 2 has strict lexical rules. Prim names intended to map to ROS TF Frames must be alphanumeric with underscores (`[a-zA-Z0-9_]`) and must not contain spaces (e.g., `Left_Arm`, not `Left Arm`). + +### 1.3 Physics & Kinematics + +* **Rigid Body Hierarchy:** Assets should utilize Logical Nesting to represent kinematic chains (e.g., `Forearm` is a child of `UpperArm`). This preserves the Scene Graph for TF tree generation and MuJoCo compatibility. + * *Simulator Responsibility:* Simulators that require flat hierarchies are responsible for flattening the graph at import time. The asset itself must remain logically nested. +* **Joint Placement:** While `UsdPhysicsJoint` prims rely on relational targeting (`body0` and `body1`) rather than hierarchy, asset authors should place the Joint prim as a sibling adjacent to the child link it connects, within the scope of the parent link. This ensures self-contained modularity. +* **Articulation Roots:** A composed simulation stage must contain at most one `PhysicsArticulationRootAPI` per connected kinematic tree. + * Assets (e.g., a modular gripper) should be self-contained with an articulation root for standalone use. + * When composed into a larger kinematic tree, the composing stage should use the `delete apiSchemas` operation to prune nested articulation roots. This prevents reduced-coordinate physics solvers from fracturing the robot. +* **Loop Closures:** Articulations must form a spanning tree. Joints introducing loop-closing constraints (e.g., parallel linkages) must use the newly introduced `RoboticsLoopClosureAPI` marker schema. +* **Mass Properties:** Dynamic bodies must have a strictly positive mass (`mass > 0`). Anchors (e.g., the base of a robot arm bolted to the floor) must have a `PhysicsRigidBodyAPI` but may define `mass = 0` (which implies infinite mass/static in many solvers). + * *Note:* Non-physical dummy frames (e.g., `camera_optical_frame`) must not possess a `PhysicsRigidBodyAPI`. They should be tracked using the `Ros2FrameAPI` as defined in Section 2.7. + +#### 1.3.1 Collisions & The Dual-Fidelity Pattern +Collision geometries must explicitly specify `purpose="guide"` and `physics:approximation="none"`. To ensure assets function across both standard physics engines and advanced contact-rich solvers (e.g., Newton), assets should employ a "Dual-Fidelity Pattern" utilizing a `collision_fidelity` OpenUSD `VariantSet`: +1. **Baseline Approximation (Default Variant):** The default variant must contain "convexHull" or primitive shapes. When the authored mesh is already mathematically convex, assets should apply `CollisionComplianceAPI` with `isAuthoredConvex=true` to allow engines to skip hull recomputation. +2. **Advanced Approximation (Optional Variant):** A secondary variant may contain high-fidelity concave trimeshes intended for Signed Distance Field (SDF) or Hydroelastic collision generation, provided the target simulator supports these paradigms. + +--- + +## 2. ROS 2 Integration Schemas + +Neither OpenUSD nor glTF 2.0 currently standardize the specification of ROS interfaces. This section defines a set of declarative, engine-agnostic API schemas. Simulators are responsible for reading these schemas and generating their respective underlying execution logic. + +A Prim acts as a single logical interface. If a sensor needs multiple interfaces (e.g., `image_raw` and `camera_info`), a child prim for each interface should be utilized. + +### 2.1 Schema Isolation and Functional Layering (The ETL Pipeline) + +To avoid "Unknown Schema" errors in standard 3D authoring tools (e.g., Blender, Maya) and to ensure assets remain modular, functional layering (Extract-Transform-Load) should be utilized for ROS 2 interfaces, physics, and simulator-specific tooling syntax. + +This REP endorses the ETL composition architecture developed collaboratively by NVIDIA, Intrinsic, and Disney Research for OpenUSD robotics assets. + +![Extract-Transform-Load Pipeline for Robots in USD](etl_pipeline_diagram.png) +*Figure 1: The Extract-Transform-Load (ETL) composition pipeline for OpenUSD robotics assets. Source: [NVIDIA Developer Blog](https://developer.nvidia.com/blog/using-openusd-for-modular-and-scalable-robotic-simulation-and-development/)* + +As illustrated in Figure 1, assets should be divided into functional layers composed via References and Payloads: + +* **Asset Source & Transformation (The Base Layer):** The raw CAD data (`asset_base.usd`) is optimized into simulation-ready geometry (`asset_sim_optimized.usd`). This layer contains native OpenUSD schemas (`UsdGeom`, `UsdShade`). +* **Features (The Domain-Specific Layers):** Domain metadata is isolated into specific overlay files that reference the Base Layer. For example, `asset_physics.usd` contains the rigid bodies and joints, while `asset_ros.usd` contains the `Ros2*API` schemas defined in this REP. +* **Entry Point (`asset.usd`):** The final distributed asset is a lightweight interface layer that uses **Payloads** to load the Features. +* **Proprietary Layer:** Asset authors should avoid including heavy, simulator-specific implementations (e.g., proprietary execution graphs) within the interoperable asset package. If unavoidable, they must minimize this proprietary layer (e.g., `asset_isaac.usd`) to what is strictly necessary and keep it isolated as a separate Feature layer. + +### 2.2 The ROS 2 Context (`Ros2ContextAPI`) +The root prim of a ROS-interfaced simulation asset may define its context namespace. +* `string ros2:context:namespace`: Prefixes all topics within this scope (e.g., `/robot_1`). The namespace is additive in the asset hierarchy and with a top-level namespace set during simulation deployment (e.g., via the `SpawnEntity` service). +* `int ros2:context:domain_id` (Optional): Overrides the default ROS Domain ID for interfaces descending from this context. +* `string ros2:context:parent_frame` (Optional, Default: `"world"`): Defines the parent `frame_id` used when the simulator broadcasts the ground-truth transform of this context's root prim. It is only valid for the top-most context in the resolved USD Stage and ignored otherwise. + +### 2.3 Interface Type Resolution & Naming +For all schema types (Topics, Services, Actions) defined below: +* **Type Resolution:** Tooling and compliant simulators must attempt to resolve the `ros2:*:type` string (e.g., `sensor_msgs/msg/Image`) dynamically against the sourced ROS 2 environment. If the interface type is not found, the simulator must safely disable that specific interface, allow the rest of the asset to function normally, and emit a distinct warning/error. +* **Name Validation:** All `ros2:*:name` values must strictly adhere to ROS 2 topic naming rules (alphanumeric, underscores, and forward slashes only; cannot start with a number). + +### 2.4 Topic Interface (`Ros2TopicAPI`) +Applies to Prims that exchange streaming ROS data. + +**Core Attributes (Required):** +* `token ros2:topic:role`: Values: `["publisher", "subscription"]`. +* `string ros2:topic:name`: The topic name relative to the active namespace. +* `string ros2:topic:type`: The ROS message type. +* `double ros2:topic:publish_rate`: Target publication frequency in Hz. Required for publishers; ignored for subscriptions. + +**Quality of Service (QoS) Attributes:** +Maps directly to `rmw_qos_profile_t` policies. If an attribute is omitted, simulators must assume the specified defaults. *(Note: As per REP 2003, simulated sensors should default to `"system_default"` which maps to best-effort, while map publishers should use `"transient_local"`).* +* `bool ros2:topic:qos:match_publisher` (Optional, Default: `false`). For subscriptions only. If `true`, the simulator bridge must attempt to use ROS 2 QoS matching to adapt to the discovered publisher, ignoring explicit reliability/durability settings. +* `token ros2:topic:qos:reliability`: Values: `["system_default", "reliable", "best_effort"]`. (Default: `"system_default"`). +* `token ros2:topic:qos:durability`: Values: `["system_default", "transient_local", "volatile"]`. (Default: `"system_default"`). +* `token ros2:topic:qos:history`: Values: `["system_default", "keep_last", "keep_all"]`. (Default: `"system_default"`). +* `int ros2:topic:qos:depth`: Queue size. Evaluated only when history is `keep_last`. (Default: `10`). + +### 2.5 Service Interface (`Ros2ServiceAPI`) +Applies to Prims handling synchronous requests (e.g., resetting an environment). +* `token ros2:service:role`: Values: `["server", "client"]`. (Simulation assets are typically `server`). +* `string ros2:service:name`: The service name. +* `string ros2:service:type`: The service type (e.g., `std_srvs/srv/SetBool`). + +### 2.6 Action Interface (`Ros2ActionAPI`) +Applies to Prims handling asynchronous, long-running behaviors. +* `token ros2:action:role`: Values: `["server", "client"]`. (Simulation assets are typically `server`). +* `string ros2:action:name`: The action name. +* `string ros2:action:type`: The action type (e.g., `control_msgs/action/FollowJointTrajectory`). + +### 2.7 Frame Publishing and TF2 (`Ros2FrameAPI`) +Mapping a deeply nested OpenUSD scene graph directly to a ROS 2 TF tree can cause significant performance overhead. To prevent flooding the `/tf` topic with generic physical props (e.g., warehouse boxes), compliant simulators should not broadcast transforms for every `PhysicsRigidBodyAPI`. + +Instead, simulators should follow a hybrid implicit/explicit approach for broadcasting `tf2` transforms: + +* **Implicit TF Broadcasting (The Asset Tree):** Simulators should automatically infer and broadcast TF frames (using the ROS-validated Prim name) for Prims that represent a ROS interface structure: + 1. **The ROS Root:** Any Prim possessing the `Ros2ContextAPI` (often the `base_link`). + 2. **Kinematic Chains:** Any Prim possessing a `PhysicsRigidBodyAPI` that is connected (directly or recursively) via a `UsdPhysicsJoint` to a Prim already in the TF tree. This captures robot arms and wheeled bases automatically. + 3. **Interface Frames:** Any Prim possessing a `Ros2TopicAPI`, `Ros2ServiceAPI`, or `Ros2ActionAPI`. + * *Routing Rule:* If the implicit frame is connected to its parent via a `PhysicsFixedJoint`, or has no joint but is rigidly parented in the USD hierarchy, the simulator must broadcast it to `/tf_static`. All movable joint connections must be broadcast to `/tf`. + +* **Explicit TF Broadcasting (`Ros2FrameAPI`):** To publish TFs for non-physical dummy frames (e.g., a kinematic `grasp_point`, a `camera_optical_frame`), asset authors must apply the `Ros2FrameAPI` schema to the target `UsdGeomXform` Prim. + * `string ros2:frame:id` (Optional): Overrides the TF frame name. If omitted, the validated Prim name is used. + * `bool ros2:frame:static` (Optional, Default: `true`): Defines the broadcast destination. If `true`, the simulator must broadcast the frame to `/tf_static` relative to its USD parent. If `false` (e.g., an Xform animated by USD TimeSamples), it must be broadcast to `/tf`. + +### 2.8 Kinematic Loop Closures (`RoboticsLoopClosureAPI`) +OpenUSD `UsdPhysics` currently lacks a vendor-neutral (e.g., not `PhysxSchema` or `MjcPhysics`) mechanism to identify joints that close a kinematic loop. Because many robotics simulators use reduced-coordinate (e.g., Featherstone) solvers that require strict spanning trees, parsers must know which joint to exclude from the primary tree. +* **Schema Application:** Asset authors must apply the `RoboticsLoopClosureAPI` to any `UsdPhysicsJoint` that closes a kinematic loop. +* **Parser Responsibility:** Parsers traversing the `body0`/`body1` relationships to build the kinematic tree must prune their traversal when encountering this schema, handling the joint as a standalone constraint rather than a parent-child hierarchical link. + +--- + +## 3. Interoperability and Distribution Profile + +OpenUSD is a vast standard supporting complex features. To guarantee that assets can be distributed, viewed in desktop tools (e.g., `usdview`) or lightweight web tools (e.g., Foxglove, Webviz, Rerun), and successfully converted to glTF 2.0, assets must adhere to this constrained subset. + +### 3.1 Material Portability +* Assets must use `UsdPreviewSurface` or OpenPBR [AOUSD-OPENPBR] as the normative surface definition. +* Proprietary shaders (MDL, OSL) must not be the primary binding, as they cannot be exported to web viewers or non-native raytracers. +* UDIM (splitting textures across multiple files) must not be used. + +### 3.2 Texture Baking +Procedural texture graphs (noise generation, math nodes, node graphs) are not interoperable and must be baked down into explicit data using either: +1. **UV-mapped image files** (standard textures). +2. **Mesh primitive variables (Primvars)** such as baked vertex colors using standard USD interpolations. `"vertex"` interpolation is recommended, as `"uniform"` and `"faceVarying"` require converters to split the mesh vertices to comply with glTF’s vertex attribute requirements. + +### 3.3 Instanceable Leaves (Zero-Copy) +Repetitive geometry (bolts, LED arrays on a sensor) should be marked `instanceable=true` and referenced from a shared payload. +* *Benefit:* This maps directly to glTF GPU instancing [GLTF-EXT-INSTANCING], which is crucial for preventing out-of-memory errors when rendering complex sensor racks in browser-based tools. + +### 3.4 Lighting +Lighting assemblies must use standard `UsdLux` schemas. Emissive meshes (geometry acting as light sources) should be avoided for primary illumination due to poor scaling in real-time engines. + +### 3.5 Variant Baking for Export +While USD natively handles structural variants (changing meshes or physics dynamically), web visualizers typically do not. Converters targeting formats like glTF 2.0 should "bake" the active structural and physical variant into static geometry during export. Material variants should be preserved and mapped to the `KHR_materials_variants` glTF extension. + +### 3.6 Conversion and Round-Tripping +OpenUSD supports a superset of features compared to standard robotics formats (URDF, SDF) and web formats (glTF). Consequently, conversions between OpenUSD and these formats are generally **destructive (lossy)**. Perfect bi-directional round-tripping is not required by this REP. Importers and exporters should prioritize preserving kinematics, physics constraints, and ROS API schemas, while accepting the loss of USD-native composition features (like layers) during conversion. + +--- + +## Tools & Reference Implementations +A REP 2040 compliance checker is to be developed and shared with the community. The tool will provide validation of all REP recommendations for OpenUSD assets and supply actionable feedback for the user for each divergence. + +## References +* **[NVIDIA-ETL-PIPELINE]** NVIDIA, Intrinsic, Disney Research. "Using OpenUSD for Modular and Scalable Robotic Simulation and Development". URL: `https://developer.nvidia.com/blog/using-openusd-for-modular-and-scalable-robotic-simulation-and-development/` +* **[NVIDIA-ASSETS]** NVIDIA, "Content Guidelines and Requirements". URL: `https://docs.omniverse.nvidia.com/kit/docs/asset-requirements/latest/index.html` +* **[ASWF-USD-ASSETS]** Academy Software Foundation USD Working Group, "Guidelines for Structuring USD Assets". (Targeting Commit: `main` as of March 2026). +* **[AOUSD-OPENPBR]** Alliance for OpenUSD, "OpenPBR Surface Specification". +* **[REP-2003]** ROS Enhancement Proposal 2003, "Sensor Data and Map QoS Settings". +* **[GLTF-2.0]** Khronos Group, "glTF 2.0 Specification". +* **[GLTF-EXT-INSTANCING]** Khronos Group, "EXT_mesh_gpu_instancing Extension Specification". +* **[GLTF-KHR-RIGID]** Khronos Group, "KHR_rigid_bodies Extension Specification" (Draft). + +## Copyright +This document has been placed in the public domain. + From e7b1cfa234226c78499086a848480cd574e16570 Mon Sep 17 00:00:00 2001 From: Adam Dabrowski Date: Thu, 19 Mar 2026 15:11:32 +0100 Subject: [PATCH 002/111] diagram Signed-off-by: Adam Dabrowski --- etl_pipeline_diagram.png | Bin 0 -> 120443 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 etl_pipeline_diagram.png diff --git a/etl_pipeline_diagram.png b/etl_pipeline_diagram.png new file mode 100644 index 0000000000000000000000000000000000000000..e5b68b68ef9beeb0ae1ad3f7d099a089b8b8d782 GIT binary patch literal 120443 zcmc$`WpG?Ovo<ti%*=G1?ERiwb?SVl z?vJnPJ~gwndbHG1ORX05nlKe5X(V`jcmM!^Br7AK3IIUA-$GKt{s~$YW{m-0b7Ha* zqUs)C$ID#tm`1pRn~hNJ@(%luO+@~s8?knMia#O99?;{r=Ehrv&^my#H$dfC`_&H9 z<4%ls9{>NMOAGA(djT{QhFfDuQ1(mJ7Sm|K06yI5?ISH(Kvy^FWuotZ4e?uYZ;aB? z;b;q*JW4>@kiNyINJNozl)k}4z422E-F!%Z%VPd<_sVkV^Tt@z@z(QCBoR3C+Eg%T zf9}@gRd|3LdjgOH05F*uxV9NZ9_xh8f%Ivx@Q2wgwJ~s`1<>~2*=&nU=B&jLAp+!T zW`%LUOf-}qq`XJ~iFuvzKV1@vIzro?Y69f?ezzP810({~A z3j2Ql2mb$x{xA8rVc&o5`V;pK+<$_ue}eyz0EmBR!+(E9{3rYmum48=A6WmwEtE4|kmT0@4iC#*=8!A%Hp8d{R ze%FBf68DR*7{|9f_tvsF+_Ron=rfTvV4iNP_CEr?fIX)#)Z2P%IvZF6Jpz_a)DYcP zXY{aI+qxDSPGp_@fctZ91fVyzZ9@IW^M^a>-_DK_YipcK`G-!wAF8#>S;^6^Z*R#l z;k!>Ay7sTghKiv=)jGa%xP8^!d!7+LLL&CMeZ6scYT>8I=?OcT-m3H z#aas!MoeQ-5s7P@t>NFlX~Pi^*mzm}?HzduwP>r&w+duKrSN$^TYq+Vd-d6oVVoMR zH{O*i`2NFqDH4yZma1}J)uaviK|{;9sDtjsH>htUG7{0n&CPf)nuyosH!9=hi)9B$ zqL0FRd3i}iLp!W$=h|TF!fV`XfCTpWVlznX5D|#-nUU~o?hX3CBGInpO+kxDOT#dK zY6%Vu1ZUK3!JM~W>1shD7^8l8D_905VPSc^KJ!VLiaSoOwQI5LGvtj&RN7>HCUe-o zwKX*}&#S0F78e&ck3YTjV0Ay$D<~+~*ys+blD)Kht_FiaL$gX~&ixLhS*a)L>B-k& z))NfJ>$8W5Ou`o!%c+tVrm&jSkS&ZPR#ce6WJwKwlAWy8b0 zqgyi-MK9zkdD`rV>XO8v3(W0jH%z+ZAzv78V!#o1x8L%{bosGtfy*+oaL|4Gcb^)+ z-e|`dtq1)Y9N2CDp?iVTrrrtOBSwL(-}!U|Cw(66Z+g4>kt{X{8~mNy-jNKC<7Z4y z2|(Y9e%C`}34-NXnuV!UCje$V(WeSEJl}r;r?}| zQAZzf>K>Bxdh=O&6n1<;%h*-dyVYa?P3C3YHaVZV?C~&yx9q1c3M91;KCMs1v?)zI zWdEWak{3G}7Mw`H^->K0sQ%#-g3PTs0l=;%?ZXHTp4GWmQZe1%2!ODy`vuK3-IFep zfl8-EXs_aeSd8(tXzbjm7j?aP5`6Xue5T&+M2CRKJQ9hJwM&ZLOkzf|HB|E2s5#gV zyRpC^=h=pjcJHwEV`ni(S7Uz!wsz^qa>1nw)G$2Z=kp*g%Y|4>byl^a;4+OS9 zl|E$fn}thjgAYiBlb@of=@!t5Wf(=)Nw1;>v~ceg`uPzg0fkeAUQ%P<;cqG0QeTPX zs$HSS$6$~f=ySPf;dZ|nB5=0KjMg4lk;GuIM%0=zlp9g&mUWLh(fg{9$_dxug1n|U zKNkT*bF^f5QCsM$=6Txvy?YWNse?L8yTb}zN` zp)2haetoXZ^qJs;zUmT}zhTC?&*I`LjM$vtID!=Q%u{NmhA(3 z3yvIOBAX2j!;CW-^gROS>8$^8lw-3jNB=(2*MC7A6(osw%jLj#Bkkv==~rdj`xTk1 zk)sBq`z$f69l}*n)gMD|yd%P*s(D6~Pv}oi{tJOB2>&l+#t?ZByqkR(z;V&DETC-$ z_F!x9&$3RCvyru{A;0@6A%bdpnc`cF@T+Czk$$4L`1+BI-a-Ks zy)8L0DKhBo<<3`FD7(ZCyAqaj#qXUgcPUnFP(d*5J1@~F^=fWh^BNtn&Xos(Jr1!M z65<13x`1+KB69h)6N1xOUWarHss*7*v>$p-JKublB@s*>Bfd$PQoi^AOIci9+ftyo zd_*_ywF%%x)GPEBp)k2ILY4FiK~T2b--2*)e9qR|TVI~1m3=$Q^1k4{eTEZ5a+TX$ zbzi@Eh~O@@vZ<49zqW46U|jcoI+?qoFrxDAy|fS&6B7d`A3XIwHcFxI$tZewZ>wL- zGgdV~s7qc?>8Wh@{dA=Kef7CJVg<3 zvHL4NQ1xC(Mqt%SZuvZZ%=fw}>J`2&)tbsX&2fvy7M|w5bMUIOTl}>K+D7tyYI?jm zIhw?wS06f@DKJBc>6F}z(^^VuibH$Q~6ctDN}{uhbhuxR2pom`rhWsb#{!fy8U-)?w7JFsL#hl1nuE{Cpup<2O^jal6wMoaT~ zx~`@R_kUBhCG^+`u!GSVg<}8d3Uh7Y)}zH+mP}&-o_El{77OLga^}= zRV`$=a(3|66tc(vJ`vb#1RObeF#JlW7G9796Kpm8l|dd_+hG0{$kYvoAl%&xxm+bR z*bQHZ9xzD^Q(-_V;J<2!(kEM7?Nrj^dd^Pj)v4QPH*+*$cZ;k@_F+lu(VUZshH*Q=2%?7e@vJDR<=UDzdJus4`*G65 zj+@^lF1GaV`1q6c^w#A^9i2)g$|zz43zWQ#-1V`}jCoL}mP5s@@;ifH*U+n~O$tJ~z@mZ8C%4NdOV$86w6 zVd-aWN6ZlCtYY$bivoFqXp;=1`nKk0#D=!oDNKO7&H5AXnD^Dfh08yyhWG19{rWxs zCzj0A`pM}5(Wrvjy^QisZz_#9;gZjos!~`%8;xD3j#GhqPmlx)R;GxZUDC0xsBJ1q zKR!oe66KK$4Su4#eGBvC20O4WL_cdBu9CjAsU7F8k>%RE6M{^9VAcMg5Cb%fx zOpgC|Ea&>Zdv;tD$z3GqC`3#z>DWLP%(nKV!DO~a&8cDoBJgOI>_@CkwC=1WCq7cc z48GVFqOM1)O^Ll9R(4NviNvo&-;jHZ+qCkwLEzc&UR09aS#&#g5$E8ZeRRwT4atc8 zZ=8WnSnS`jZnZK<+B7y^?wM*>Tz=hcWf6Q))_4 z2R`$YiQW$FXhY|Xjo6BXkA6$cv_c1|))1O$c2GK@M5lE7>9~9|J0}=4c4nA#RR>2m z^;Sr>awlgsJqH1IS{1pARTn9cg+U$`*kBbVAKo|CxVVRLqtUN%pM zXLhF5*Q+l!7UMozP+nzaZ+k<6Dl?#OpMT}T86J^|z>EDT?h4wjz+LxRHm%RX`z4D_ zubs6X;*ip;696^o5wgGAC=F6h8a z6hneVwSYA&j&<%qeuU1+JG&(R;+!M5V)Bhreb!F~8|o^LTX-i%&cO3E=9 ztWS+zWXZZnk`8IHK3n1I`hqiX@gzJ{AmNa@GXHeZA=Zm#GO#-DGvJSBR)Zq9LERiqADQL@s)*^R21?DOQs?FdhS_Q(k~D$=L1ntIoTJ; z_(kQ^?AfQ?xnfRl5D02{gy(`U5NYG;UYC3RMe(@l3hiV*d~%y3avS|28ZzYbtISt$ zRGA^FZa3~udYr>WAkSqcC#0-kHkxuEybS1df(w2-)umi~CShz^*uV0piAXFUa$W$u z2A!%mc!>S=vf5c4i@+%i1wFV)j{6NIeZTg?LKwFC%!5FWaninR4Ti*u80_=|yYIW1 zsV*UN@Rk6NDHyQBGH@KVnO78d4p44Dq?^qCc~{9-zec;RD27}#Vm2)U38eEi?CAJ# z^2LJ$8~-5r#B@1Bpt10Xabf1sS{E6V@|i_e+;5UgPk9Tas#iI~3m*55f?SOTwfpN4 z1nCEvPKbHz#CDT4(Wq4pUoI^0$Nq(NOHO9PzxGZO@U6q{+wdL=`PRX9nZF$8uhi5y#dGz5$6|eq2_f1{P&-a>7vkIYAClU zF&Vw9a^@DYM6+pbeja%a2iPyF%op8+9ob`by7oiXj=%X>94(&PCVbm{;Ottb`ekn~ z$AW#te#8MBr9|V??{$CC`7_r28S-$d0A2hTcoz-7Vc%HUp{X-9qt-fPcf!L$lZWqu zem_`y-OT;oIm`H3>z57dNQwC1A3@#v3sTLT8eD8|cyY@1)s}jSUDb4TG?daRACE;l zcal0sq|iVr*P4v!6tpiu@o50=!JWgg{hTxFhW&x4_SwQTFkUY;qlOYk-Wp8`9FIk5 zk@3VtRjMF_nFM{U-SleI5b{o}E@1`@^_C?P#S)FVk!cg_TsgZ zr=8>lZEpO@@#S53USUI}G}3vl52n@+2^JE5*^ra-CiYyW&#DDz*eW{@TQU7r_hTrL zw{Kk#$hfZ*Uc-S?Hf*0PE^YA9va#P9PDch(PCi$UmJD+mVFEOXXn0GffSFcJw^9Tb zY+S_qFWJZSwJ8t=QclYLS=nB{60!x433}vy95!A?t4ECI;s>s$l*`2!n5B;hckfAN zn^DAc^Ta()$*5L>k>Y7N;TO=B6kjd9m-IL3r6h-DC46b15Uma6B8fE~-eq7lx{plr zC!s4}pw>ctqiK7-jvQ9^s(4zh^JD8h(cZ9B!Dbg1B-{!G@)zamTSr6^Ba+K3&^})U z&YsDhKp9FIaKT1#Jw`Db-#y4VBNr>{0LIn*h|2>@%jZJbZF`2=5&S*rR zmUKCFE@zj?^sm9q;@9cIL}I>~VVobd4LRWEJYqlAZh+H~Xalc?-|X3kU73RWO-Qc3 zeSlDl351E23GIt5lfkg&&l$Q2LZ?)*ICGs?qZgC+2)`T79<=0S%{}`DT@GeMA z^JeN+_BEe%tHR8Iv2LWoOEvYbJ+fAJMZRL{?wW0@E9>x3OVT3~_J|dcB3i5Zv!UPi zBcXA4bl&t)%!hnW34HI=0z&BH@Ml+C0etY@ENL96+d}v-w#gR)v(S& zVL+Uj4rTBr`t=1XlV!H?jToWF-&4>mW@7`N_FtXjL&e96WJnb${YOcFLc#Ig*i#jn zU_HaGC2#Uk7SWHZK8GB*llKaXd%r}$?_ArguU7FF5DJ9Zeqm*uyWpY|URS$c;u)bP#)g`rdsl+Vn@*1^ryV43rINa#>iNcge1}axMK`6vj zV#7tUx5a!s=&SXw><>8BVcXF_HxFI*Ygfwja;6E+x8umTZ;bL{SD6LF&&9qfj3Fj#XIPI8!*i1 z*#l=DLO{Lfab7Cy=E0GFmv>WIXLff@gH_2@x(z|IBht?(r@b@`LTyk8~oj<5nho+#B`yoaI`4XTw!ZTFYeW1}W@=XIKyYMPdP zbw74*E}guFs<(oi*8H%92Hhd^@K@;qTE}+vn$^b1dKnf==r-xoAOJhEB8K}=$G9^Q zRW_mSpM(Dzp7cGCpI`4!>EZv-^FhR@U;a{j=h&bL9oSjJ1i?b?=GJF?FW$Y6O! zxqz=ydWF;~jvOE1F@|)Cu0ZK0jAybVWA0fl;>K(s;1_V z7u$<#Um>(IJD8TW;TxNRja-fANU`ZAsA~p8O`il=z3Dd?QGM!TM)AML1xtVzLCOf)2kpmu>qOWOneI_BuQ5 zI=18D2X2zytaLSm(6n9yp498WX8M+)g6f$0F)!Gu2{+m2YU~ZQd+7bDRuE*mJyEUI z90q#QF%R^wJWZo?ju6e^QQ@lIc)tZjADsnl^v}oaPi=~OcOd`Zyqe5gZIWZObgwT9 zhDk%Fei_~gl+4vvDdV-ZZ{9yNaS6r-S_)m~2=9(Le|L)qdq~VE4=1bZU#u`W+(Tn?y3Ao6BQaJE*+CKtk$4`ooQnX zLzRJ}HLkDx`g75p>~Q8T zJ`?y)6T?;Ub`H_ra~_I6%|2sKnGi;tS-e)P=4W+IS!S?wX#we$Pf`nvZUVT+32KOX zg3I6*o3U(`Suv}TM<4V2u=!3|(o-h=OduBbhGP~C@E*7an_pG-mwrszJpB&2uNc-( zet8)TB-ti;)t}ECIQiB>J+m-Ef}3taIBCB?AA9=Ebq~qI8T5i|^Q^kca!0>Bc{*Q< z%j1ob)&Bq*zn5>X9d_r-BH2_PX`FeuUA(t=Dp{HoaE&U-`}XFSadhveFb{J!%+a#9 z1u_;|Yngw3tDAe#$e+63tLyMMs`4W9Jg8Va<-+`UrDI<9gXyWo!A3*)3gg&d@dJ1E zxRd@O$gh-s-1oL(jyT$EJr@M`ri!I>yKGq3o8aegR#H>p`eCs*KA9lWJ~g@obkm+KzRS-UMZrj&j zTiAAJ=Xz8X_P*tq%;BsgRLZM8v9slwY;yDl)Z!OPuz!UCfQt|)pinC)7hf7Y;qkP0 zJ`m57yj<`WMy2<9ezWT2s3@yu99_&>PmQ)1m`;CqJP;HCXl3f#^Lw^&2*x(-GEeGKxS@IC9l_}A^}e<%MFh%((~H8U#@_NOm} zM&>390pGY(kpCmiHooSUuNdH+awt8g$sCky!JGb^luigs4$=zCG)b$%LUeGNyi^LF%ruzYah{}p1PG7t4$IS8MZ}5PT_xkH1FPXLz(J=c2;r~wk z!N0mm`j-Iw9~AiCSpRz-VNe#zu$2cZ; zz7p6Coiwgz-L3lxXTEQoPz%|A@_pECzM2rYn$nUmH9yl6>=SXRPzO-*8J}xet?;dArzj!@u z=yq*u>k||<>F?>@bKW^s;H1u@N`A=AHXNi9Ohf;Vl3Pj$6_MJ zzj0VFXFLgW)Ec1d+x9uO*gw6zHfFbbw`ZBwYSUpyuxBdm(lqHY|FUbON>xaU2-$U_ zi|O$YOcu)}ZPrtQ4hndd!<77hDaiuB48B~olTHH8;uET(h1wGzH!PP|>sHQ7iF82c z`gE>u4@Rc)Wh(LbIG(TCa3`~XmO-RT+ax4c4;dxszE7A}7Y{61+1a}X2eKPCH%VMt zqkV3I#Aoo^A-!M(qtVYRk=c5N;)OjApblN6pw-Xy#+`FQXMqNnlf6Ra-^$i2@BD~Z zxaTj7O?J@<*5H~wJw4G#r43^8Xv6=0KoAo79~_(YBB{C7A=Y8{L30}q)y_iJz93NO z^Z{l_FWK4I*(L3BrgBHNFVWvLH~@HXQ2tb`3?(^nj5J6nyI|T%*P8;I{py;p>T9o& z$^PBbcXj$H^ancL?b1aXIY#W>uTuhb@~U)3r7ohO74t{v@L&2)+z1Tr^%=3jYZn#R zQxUJ8&>GPys|)jjKVu)imR|nQDVJl#HH{f~v*fICg(lr;)L{x6-0ri_Qm5|^C8XHV zCC!`v%%#h0>Do`yT;(LSEB{@!d*YY_751FRv&B1rjSzX9`0Aleff@r0bSaF89tL?f zpce{A;m%YVjO4rYY8Rwlvum`DNZ}pXWvB2PTPxPjjo&>vQT*FZ`3?2z+iNQC_~y_&HrV1_$iZP@z6o0A z6Dak7NkKiL?|FcRk}ugNin}Vlr;FNk2ZgjZD0>JJ+e8*>?VBMw3Zm&(t6YrhR<}H5 z_wYjgo(U12^XObR@kZN&FyAt5i&1|5S{!7R;i3bmQei2hETq zm#fDdGHiw^X;6QX07MziFEp1`)=oGJGY0uvV;A)pxWf2uIM-4 zxxoqN+K_kv-e2&6#a_^mRXHXblp=25?VLYsDW_XGg{B#ZRA zjKJOJ3WvFWV9!m^{T;BJg|@orxjVlSPkxI7cJF0g$aU!4tOt&(Y%Buq-^GF}$$T91 zk}`&i9CES6B24MpMS!wYrV-!2^k7CfNlx(}Y*z-U05g?LBK3>a_269{VA;;(xrFq) zDs;-F1TG#w*Z1IMRo@v`|C|`;*FRQ7^`&D?o7_K+>_rZ7f{dx&(({O3FaW~{@M>Kh zXd;Z!shr;|TsUzH5AVB-mUXpP((CekgS?6%?;t0?xyk9RTXt%$lYYK9;XG23 zl#0ISe!+C7G9ngclhR>Oifh8GCN}7fI&NkQUnlO(zAs_vFf#}rM!(v&7*IUw2|LfK zg!A9N!1d|7nApE^et}=S|0|qz)eO|C5tpDSiTp*?BII;+CI~qvHqRQX1C{c2pYp(s-_| z=#@8(H?Dvtg`1lj@3QXN_A?rL-`)h@_A?~N<76n=!OlCy0(HMUffW-F6JrlCn_A43 zY0uu@^TNQeYr+;zhE8t}#vmA7O&pLpRFLc_fCHLOPEMG1&~x<~?J|#IMfzlgzcj%g zqaY%}hEvSQ)EprU>(zhOxH(>|E$Qs+Ok*>FF7!IMdUsA*qGzxz&X^@^GI{s6{Rq4D z1p$X%aWiawV?=N?~cM%Ap5MV{mK2% z3m-++^>%MfdfYk=WwXu!@&I;zejP=~tIr^?d&CtQeHq@sayi5Kicj%$@u+(;k%{}p zZ6+orvrl(tqZ~`sCemc>?_&zpRNf~6ig)?Z!``bQhXU95HzdC}SDA=F1!L%_LvZ%? zfr2uk{5|h>bOUFse{CP2eT%4b@G4XMM`nj5TDKd&)VYqq1igtDdgA-UDh`QLx+``^|1=lH8Oze|VhbwagZ8p=wh&xmy59pM*wyYRjud^1bbnp_Op0qQ zRD3mlt)oohZ{_uCOHa4G%`(WP1SO0!1u@I`62#-#Z^BF6suH_yH=kKfC8 zzW8_UcYoX4<@;&Dsr!jaltJ!W5j;=!e5HZB0;aR(A7wyK1<2GUSKuspEQw&lgtmc*D0r#dL0sM*DT<9sGd9 zqa%h1%mQRSpu>iUqge)@^N$wyGkw?Ng=+MIxkAWb!`q>u(5@DVAV;zQ@P)ujrnBWD zKZ*2Z=-it|HfJBw28NGiB8YrO;U=#u&Cav+*7K0_P$y7JaX!`oMal6?{Si2t?@l@8 zcB?HK72@iXS-=Pp_!jS!CRXz+Mr*hG^UWG1*ec(2R->Pt5AIhNf=%IuYi*tynwpxf z50_??S?QsytV&z?b-JCtz&O=8R5lu?>!g1*L8gua(%0y8rMW&%TIJiEky6iS`!xA` zF`K1hh`%F2R$sV4Q#|W$q;aF`{jh+%gGz`9D9X>z*QqiLcq&F_o`*layS|3SbRM6E zUOE0glIGUpeP_p}G=)^<^W?_-XxwsmdTJ*-$!d!y5FInxIv7VG4Y_{6eL_KxD!sRh?ZL+~HY~*JsmtBbhz7L26xuk6X3r~XpF&}0x|SGi z2E#}r(;BD*@2LopE7_c%+S7%~no;`pR`kWJwo9C0k>~{$eM@bgwHExvR`8KL4chP? z(H(a+c5@1n2H)QI7uUBsZH-ZrU z9N=-{*QgW|n0?rAn0;&Q-tLQoaZh4DiM6HT@6Of@hOQ2#3lWNEkps4!HX*fJT@oLgYJYY7U8t!F)Eq2c?1DQy z$Yl4^71_>>ReA%cuU6swDkmIvlVb(osTZLLddmwY`U23j)M@YjSgc61NqwiH6l_2? zna!gno{q@_C1F_7Y2gxx-^^(N7w|OpP>;~vhYMe&yYy})U0!PRNp#3R_GmY)W!jXG0=cB9&Q00l*oGW7&f)LVFBQFl=x`Ki~7`l62OTwlC2N~4&GkksAHS%5pMnxNo!he zzHPp|>GzE0Bx?gdc+_Ya_6(XiK#64pbGwUtg10Ocf{n-NesgG7#;UM)`JphA%@hd> zV@Fs)1_vLF-Pe54GFz(2kSSS#rVr+Fm58X)67Iosd**IO(bMZKD|WovI*+edmtsn2 zc%!L$gRYL3v zOluAmOPm+N5kw!O|2*B0#D3xA3a}MhsAoA zR`rXgBAs0CsdA6ZFMZpfl1GV}(M#4LL&{Lk_)%2@Q9*gn_7iSzoyM-hIvX(?DHqH^ zeqj0!FkLi7ZhQRrQ~02y`hr|HMDr46ODJ?0 z8G)@sFE9@N!HH~$3axMYWF zx6^WiJ~e~TI!Z7y@Zj(cK>}m~7&lo?nRrfgJtczgMRL(ZiIO%lVzkR#A5E7DDdDaQ zU2wYVkEFczLBqf}T0cUC;E)y~sl!a;o*sO8Z(&ayy*CQWsQhV3A!R7ez!PUn zgaEtc6n6Mj6U*8?Z>4K(?;J3^_BLJdqX9~ncR%-~pQdXr8CPSF<5cjLJW9UXMg_)} zpMzghJIgQ@u!nC8MV_?9=Ow^{vQ!mM@tQ(R5s*wO>Y}ZEevtXSy`J!QPAAoSue)dE zchsXu=q|$-%iSs1ZkNCZIEF(fapvWBrTy}(sGXP)VclyG|IbXtA$$2M9^-3-pQU9{ zi|-3RxGwk@EYq)TDi6l{i4PQA_6#|N%GuRY{TKJ)p{Z`N&ZZ*MlC{`^R1$oMGLRxe5V7RE_2A6os;bT^v9f+oC! zUM+cfJ#3Yy3O2mErRnsUDX~5+<;Xe(uE&ZI9Tu6I+t<3V2jIAu_@Ucje}c$IXIT~5 zW@S!Xn?X9R0G`~6S>}7^s`zm63-$OSF!F3TfrhGjBh_V@Z|jEF39xS= zh`!=`z5%wT1j9x$J3uQ%#gbvrm3a{cp>HgbqXSq?wOa4=8(gF~5TR+(KTlnAQdFmG zgakX{-C5u@X!q)mQa;*vRx6>61sI9tDdMJ3s^TVE^5$sZwr5Zoeu5f3U_22)&2qE) zI&vn{Q-q2$V{w=_Y)M$*CksdmX{gJjw>2T0Q_5b8>g7O=Dkho5u0wwLF}~bruYt(> zP5bhDHF?0PqhXE3=kaF}8PvXep!=PJdB)^*`t7TOPG^yxNO8nx~)RdD0Hv8iIe24^@8Z1}d02K@G87d8!PoJ`(E`jM>x2lZeqQ(2J z5P?wy5UY8$Srk?91l1VKdPhySk6}a+O*9$<#)GWwblZJ9ixY0cdpmihYCXTV8uFTo zjaOIiotq(@^K_x((z5VgC?diZ0YqL!yr_V4y&~FWI4MQZp4EyTB|0Ja5uq?TKB36o zFp-I1Xfs!>8zj6t+FfMlYJz|y9EbGV`>Z-{*=fA13t*HR-o-7ti*GhEbR9z?OsO6@ z*@kM1OytKfU0+$u^>Lgu*Qk7aJQa+Pxxs0qX72B*?A^xd2AX#-IvOvB!>dl?-rJf4 z`e!*p<3lJBdPERRV_gT7b3z@xoJvlE?#~0XrBGAxhT7E^u$edo1#P^QLD>jvFAlD< zP~G+|0Udc*mdJV;dp(;Mp48cSYB~Y0l+2J*P(!^3N>@M0b4I$pMQP>;Z3r9zs_W^0 znsLI3Csdclo*o|3TZ7LHE$MJ9iEd;}+4vhO)1Je*tbT0()Y4uSn z$cu^hgbFcMo${wwYPR<`mTwr~R-+Uvv3F3pzTYj1dyU6!|F5yfO z7EieQRuPM#`4q{Sh`MaoLn}znH8(bzx?Jj} zmR57f%EmkFb4X6v`_@WbQ~7*H(HUt_$Rb(YNtKf*s!PsrP)-^Pyse{rIl%XRm-J_7p;Hvvzlbv`ljx)Y!GewZ+WT zx7Uho=ZUQG!_xhv*Owi^(=ovlUvsjsdDqo>pxd#QVzv-)VlfR25UW$~R?eN^C)1*% z$^?bEug1T-*}qgJSh=ihS47PPA8hz4ygfBA_(pRU!W()j=}5r`_AH^+!Su@jdVJdG zQ_11;DOX)CFO3bRwye7hzpiQ=cNToSe*CqrES)V105IM0b{8>U@5uMQIawh8#pyeO zYTD(o`{Uyms>hSra`jR(Gh0UF&rj<}@$@cl0{%hU$XonfCwIs-0!60)=b8r&oIPHx zv+aa0J_#?#q3J=3%v~3bLO-s>8j+Q}omIQ$&)GW6o%Eb+*b%x-xM+}|5pg#fN`$`w z9LN$A2$=nymX&E3SCR*YLwB@&gzY;zADm-W@9y@AThGp(9-m|;E`UUo?&N*lJ~*U& zsHaD*Ripbfpo+oMqeni__>T9LvVm}Oe+|-PNqZJfP!y8m;JSX z#II&@pPDI9E@t%ZhVON3Kan_lQrR4m@@OLIwLOK{`m*)zrj4rHEaAx3>KWuLq?McU z2b003zkR!aY{-EG$h@B+ z{EaJJU45Kp^6_;UXeeD-^%^`XY&KrAF7%YTd`l|5SnU{+RI{7fCT)Cw?sP`uX2Ir9 zs`u?M09aPm!5oh+#XA9Tkk2ZuXgQQ#PHTBwsRgW@(!gDNJyA8~t%gB0?m61Oz8`O> zTVyywcfY+M{K@zqz}&UlEh=y5KiZ9NV{_`qY~ZxMO-YjwSts-1O}%eiX`vu5N4Jq% z?_f*IjutF57y$h18s1MO-qD5d)B=pb8GGpuygoHM)1LkFhK=vr)B2z*5$!+&1(oE6 zFq73(AXGJS4>lyA>)(G|*dVQFG>8v+(PtSaXaJ@v=%lLatTXErXzKfD#^lW1L)QB>W=d{&4ys)5Nt% z4xrORTTL@zd8jWwfb`$fQ-9Fd9xXlnuWxMmTsFTQq6pc9bUg^^hvTX2fscs~&QKYYCfSXABjHawJ|AOb3&beDpNB1o5% zQc{A1pmcXP($bw0(w$NRh@^ycch}GZ48y#eN1y-i_x-Q;d(U+-)R{f|?6dY-_qtb{ zvC{a_{I`a#~a!GseId;V3nd7g1jDZ8Hi7({pu!+fk>ChU)eh5nDQ zUysp(qUHFB-XMp$(*SEW87%vNIsf8?+8G~VqAsMimuE1zW=|bIU50%!w+VDT?ID*-mBBz-@$pzX82evA%TQ5_?TH;NdRLi%RR;Kl z|BRzcCWG09i}@CL2QsbjH=YmV@)OH{PWi8KAdrk1AUf3PuchDQ#K`5!y8mq@Vpa`W zn^2#n%jGCXbQ|>*s3aY)#%nYfyrIXqzDAH=P|OJ=SE}0^HStX@F>|}LL5@Vnt(+Jv zhYG`=Qy^X-5d8kMG)Ae%@JQo{WpkRxg|Wcdf^X7G`vQj<rWr%@a?zC^*e(y(vH zpX5CO+Ua9e*3|-(dPBx4KHr8T6xDR)v=TX`A1-i@3%#cFj|#co54tB?qZeC+r6X0w z!+E50W8X6oKu|-4Epp{jmCN-c9w?N#RO6rR!m4@&odpihq949+C<3f4wJE3-yg1p; zWqgxlB)f*$0*YjF6|*F_g&b#d;PbBX>pE869@9+?V-!^HcDj^|JpzzgaXtPSjw(K{esI07P=X?45I^Sf(j=Z2wr9l{|P`^5Bl#OSX zwzn}`WnpKR>xitkhdQ}e zf{g+-S7T?tH8#rGNuD+9FstHub(C&DoFP)b_?c`ZPdb_ub^3SRjm>MHcwV_Rp{@`Y z_f4q7!qHv>Yz&lVmoEMY*aphs?dGj3H63>q-y64W7@%z5vf2a} zPgyLX$Qp~L6IEDv4+7k=R}dS(vb$`24XD!lc?)~N-JFRoC5HJ$87%RZkP3D>u zj+X}y4}?&6J%wU>jrsm=Z6b)%`D(mMz7j*KO%IC+Xx4)HLn}7jN@1oOO>J`^h4*c^ zz-a<|)A0~aNAh&mdyr~C*n(P#mcM-IgOnzi7cr;0HsBHp$Y8dT!Boe&2d&n%GtRIk z_>#x)w>KfW-%B;QjbQMSe#g-(T#m*J=c6?V^aUSW_CZi?ei!ZCJnHgjARKZP`hbg; z@QH2s{MM{`~Xdp&a$<(jLG z{iup{Y5TQprV;ymmT<;Cz`IUf`hsAezt5&JRMN0lz^YPcp>p#fYO++dss4-Lg%K0_(m?H9^=Y0z>okatBYoll zdIV+d_IYDdZpf_TsDhY`pfrKFu*=5a*K*#q=YD5?c-LXZcfJ*Ijg~s8Jl(3g^ObUBzMI>) zy#}$D(XtO>VPr4ZePAVBmLqwJn7;+07l7_^$QWyN_EfcCqtO|-8T_d??%adW4u15# zZC)CS<4~j0;7#mWxoemYXc6+*=Y$d(?zq%)sWnofHGO~V>VbY0S3i%~Y=a|Q^arPA zOC?$g&ZIkhR-aoOB&*nWGsK@E!eOSM!_brswMs#fV0<5|^bPYjm+MUiVGj=sr%G4N zr~g_PB8ZjnRP3H7Kw+P>7wjg=J}81f9;K_eF!WW}Lumws+Lr6$j5>2Ih>|IGYge0$ z8vW#QK3u_hvIjC$2$|v5CERIThF=`!oDKU@`P6{osK$v4rxcj#l-QqxAJ`{xn-?7N zoO!gMVLO@o7)>uj8V%9tD{=S*=LZnYK#$|p@C7Ygt!od~nzf99h_@> zQu|z4(5x83-Q{@}{iJR{pd&slYt^_ZF(L4|8m&LVkby-&9_YXTEksasIpj1Kj?Yql z{FT6|_|r0g+$Ip8Z|4cjF&0{Q-V|X}g<+F}0O0Wfnp15B@9BiT)&XVZ4e}I6pO#$* zw??*Y_fQ19)?}153SB6+bd^}tLSkjRA?(Zet$j1UkF7cb_*N~mj{|_^7)f}ufOt7^ zwJgIigIG?<20|x>d6~LzbpnNw3585wp1B_V3Phexa~P1;Q7Aw?kalD53?&fhYTC{} z=Or=qC@zK0SEA|it!M4WB^FTG(Q?5KqJnEAH_SLEX)uqNp5kfQ)kaxBm-V%RV8XR*2NY+H z)9D|N4lGd7`_?7RC>qM}fpVZ_rj^{U(cyi`FW}AUo(nx}rFH|hYOAh`TG*?e zN<=OCXY*4HJPR;Yu{5j&L)+0SOOGQmp;Bn4(e830LCKDz?tJW(oCnW?MeFZFLJun8 z-@|@`E?M@IpW-FhaNapWYJE_U7)973k3NW>g2=_#MZln*kLnvf zb`t>{>R!KH(lC-Kfos1xB;k3vOoe=@FJeNo!p z>9H@!;!>9vJpWk5XfxnGplme!EsX6%z;{8i@XGzR8oc36q@keG<<*y-ym4?6=4I=6%QS2i8b72i(1VCAU|%{3XGC(b~lvqxO+a z2z{;c#pK_M2c86Z8CSIu^i|lIg{CXd(4B`wT{Q;)?J`LQrt=1WvWY)w^ZX9DU)>Lyy=az27!b2yUVTzmH(pTn~+O0d<`n+mB_8x zhFZ4%UiP|e-8zg#i^63u_o@nG0JtzG$(|W4sB)K-!MAbt(t+v2H{vU!kjA2d1v_Go z%~sAgAt>76h~+PQ{kyKT6BZ?L@FsHld4SQDZFLHtd9H1PB#yb%qPqPy+*#Gm`*7{N ziB{VIJ*$P;kllKvdARixfj!Nn(#33FjB`1B9`A*Bcbc_JwVN{EgbQ(mN8j-1C@gKB zYPxc_z&t@xytnCQxaz-r7kZEx!X6A8m^TKthVJ{~0}?r6C&qRFn0Lm61n15D^}e+{ zuAL#mWkLOq3n4sxzwU83#+XpMw>w96a#fc#0|E`3d_nak;V*WIj8e7IG!krw)%x&o zB)(TXenNx!AfY7rfv@{11s$!p-i69fA zD@V=@)2Fn_eI|e5(|^RgMj8a=$AJaSmIxs>mQ{WKe#Z;R5tXOj=u{3i2>zRdCnA5( z2C#P;bf{w5s_11O28g4IfsD_g=o;k}tCx$S)Y#NYMgT}5=mxaYKL<6Mm-!Gd_<53) z&f)-xCKqncQg$ZmG%N{nLu=o&$GZ`i-W9CL%aiIp2Y?#UYT}+=`{Bn8s%6`ry(7be z;c;ng#5!;_j)Af}vw!++<>D&w{V*3+PgCiD>}l@s=ET#)(7zuBmaj(IbgU?73kB@a zD+Tw|AL1?WJg7*jr-Sx>la&~>B3A3EjxJ`AnETI} z2(=mH)=EQe+q$85&FFQuB_Nrk8h>b;% zz=N28^?9GI_Qp313HczvuHY=puvzVCmZQg*N$QgJ1?#TZuu~yRf5UALcyKE}-RR2Z zYs@tn#;^O&=&7~N|Vml#} zTbUs444Cici2$Lh%L9bk$&zht%)xW;nv;wm=dYJ#h~si zH!=JBjY&vk!u}500Ff1X7QlNh%V970=ZsWV3@3r}qztg!1ROYDD!>`g=HGVsOE^Go zLNXk7r||2TZlbHL@oi9fpZQ@NbhkBiTMIHqVs2A>bd+djL%OE|$Cr6=8?@_E0UgVV z!w(+$R{4*qWHFFi`+G=E}sf z#->Fo>?ORPh0%)|%aI-fxBU)SjS30TmR1pZnW@LeU=w!gXQ|2JZn^_ zvw)-*mV1I%SkkjLw!qA5XTMPjxSUn0pTR+9{0OD%4&nIBr+BSrb{h(}NuN-UG4CJvV&55y zpb^tE_X@kFjfG{%9(XCspn&8UKr+B?FJ~a<;V5)RoU)qM&N>{ay2N=Qw)h}an(w;x z+5nRkQp_($&V!~%$wZJsy{{UliRX;?den&TWk}&9yHoZ9f9fAzcO_@Zp7(xn_f|YM zH3y4k$}ljTz~qe)S|w-vvrH^3S`kCF(W<5+&*$@$!qCmhA*zqxm)iG+gAaLk(Q~qlU%>+QG8#aNJGJvwXG?OyvpG#>(E*H-Sve2`PdpO=XY}XODakp=59)Y5Gm>WV5M)LuZR0* zC{5oHlTT~fg(Fc+*>-V>kX4L`!VI@!jF?&LyzH2mfqy1({Zb~;E3-|^Qp_qdDkQ~H z;M$8uUAu4nX>Wu;|gW8n(lHnC(>jA$XuY|smR;~!7Wuc=)~Hb6r) zdf(L-{&eyF=L)7{8n6HL->~NYdb$6Fh5qj=16JP4T$w%o?S~IvD<+E$&l_u~{*25_ z0MSj3>0MXJwa_}*p4UnA@tNTMt8<@#?-6pju`)UDi>apXNS}Us`rv+yS+`*h9HH^N zKuv9&U2DV{g^ZQSz2=Lr53dK{3uh`+?G(1 znFxNQ5j(o1!nlRXifoz04+6c%i}dX!vqF+c4JYszI|@V-PdOv@KK z*`q*1uIo67#1^WCEg+ewJd1i%3i6QJuEwi9u@@hg#8nCv#rl%D!yxWJQm#>46RH)v zKr{Et>7*gmXo(8j>35`j6>$_T%{~BQ#+ySqCK@&t!0V{?_;KUSqwm@wYkk$dB@M5p zGY<4SUx|JN#AcG_)3~6!j7Fndqf^x%JrSq7bgfTHRuWia**XObex>BQdm>FiK#7Uy zFU<^Y%+sNs?PK=Q5my*%Pwv~cF}he8(>Cm^DL^X_w@3kLqeF7mK z^Fw0c-|0f><84^D&p!3sd!DDG1E5w3Kt1^!&6i5oglf_=<4n!Zc)w?OZS8*Ceqq!} z;W*;Fo|=0LxE-Lt+rD?9^*0f-=KCT#SNNE5Zra0fZj|kL#itAS^Km0U;(}mOT-;-w z5<&NiJiyb{1BPHU^Bvc1fUj}RbUcwKCZqM$TL1=_mNaXC2GYv@x9)>joZTMp`UZ-^ zDdY2;yCXdj=$)CX!lt$*Boybw#z1iN}+}dFmbtZ+tcHZUCAfH zguF8Xf*8z0r&)WKjm3bI z!l-iRS)bC}*S}kvT=FFc(oDu0c}@QYQUOA~BQ23``GIXE!>s(N;<-*r9|FE{TXS>% z$D50F#^h08Udcz1RPJXVFc+EJPhtVWd|n%6qnVM{Ebp?%@+Vo?Kq-+ zuBhARjo;p+mjHWi3~M?aY87xb*}FWyFzCPojMRWMMD4JF$rE#Vyhtng*9|FlBKJ$R zQf&$@w3(^SlqdTKg6v4-OAORY_>4ML21t^3L7t31x8G8p1m$|g+~!jo09=hGJvXg# z48Si?gL;IPmSqTE`;60QKk>j#GcA;xt&eoNw#BR}CFG{)E79wJENTle-D61d{RH#< zEw<8)naY8&ST*hZ>*z!Y-`-$McXU=;vqzJQ$w=AP=F2U%+ia8Y79_lrwiU!`c(Lbf zdHd3M--7PKg%)g+lY=qCd~ZbFv$AQC_5-yce05Znm}VgHzI>sy@N|2uq!^>Y zVHEJqMZja;90%m-N+p2g#;XM?8d??Kp-|1MGmp^%l@R)NFl~MEKRQbnXxog}xYQhw z9l;Cyu7cH_isFWQq zX-)uv!_B-w)b#w-H{!nJLIAT(CM$AS)k=y0`ZYyG?E?2T%mdj_YrgFuWX*B(5)+P3 zRRTO+Bj5(BeJfMA#+Ss8)H4*bUTp$@G?ZQ#Kz@D$CMGwFp(KC~u8(VQ5!86^{xJYN zzUdXtFbeYWvF?_|^5-pXimC6E!@rR&pVC`4pUGK}J=O#woLpcRnxpGBh z3+=wsc)ZesnV)(So)4BO(rMWp{EWm@FW2*b7~kmV(+UU0g}8d$!o^W=O1gih`47X< z93SkNO)eZBjK~%UzrSw7+G7x{DnjUHIaFtTJYA|$ZQ`b?{GPn^@*}s%^sHlejc~Je z)mFZ?R<+4k=zyC56S{{=L(M$GiRmuw2C6G7d~42iPZ30M>{lWsJC<6lZ%bqO`$uL- zNn59Nu8iN_8jU`0DqTJJGXtx-K$kSOh_lx7-a>W|?cKd%3%k_=YGz$3|3tEGtHVrc< zRMK|fm3JyE*2N@*{>%~pl9o7*R5{smx8oBIvI+U0s!8)0XDq?N!Btj^ZR+Z-lNFyh zZ4KTY_$=72_m9@jdyp*)2i6!|Y0=MzMJHX4@&{}Qg(ld@A7=Za*);hV;dbwls`+C}NAR!$sP1)^#7V01D ze3waX1jHcjVYzn)Gmv$Q&uNkx6DKj2)2~XH9!L?5MS)M0UNPwctW~#3CdGC&HTXPBT$u& zH`4Nj6-l8t^iOs0pXg6d)J$^Mn43-idcw`B_*Ge&fjT3P`hFyiA|^HM{w2Ov>6B{? z#7(GUyLq~4J%#1y!&Fw(ETvJ z^~#}PS0;x@@a-E*fs^%8OhE(46ao8%&X=`31x2SK&qIdA*< z@$tRiGpHNO2MI5*RNb2E>Zreh6TX2GWZdlo%cY+%Bn3TjATHvwD9wCLAZZ0LsFbD> zEWa1_>LAG4lTl7iu4t988*PW7{OIs-3AqTnx=L&RU0=)jcTq%dLjGAF)(T5Y%lyWg zo}JxY^TLIGgG$B`hnEzX`h_0Q=4J!Rr6grD_CyQ1S6jW5h(dpBWD%2usl8S~(ajsxA;Kx_@b*6i_ zuqY!}U!m9DB#3#}NrXG`j1-Tcx;%Bu1JljVxZR=fbEoB!??QN2SZdQyE;Nexji-0eIkCwjWm z%EO6iL1o3w!=-#?Yd~-k-JLxd5Ps%OL4Ri=`KYb_tY`A05Ka5TYhe<_VSxOzkXKe# z*u)SoVN(A)1URD9qMFYnY3~mz6%R%^3qjUzob5HHR926f_2>5ss^jYMtsg(e@A0Yq zXxlPP;A2HR(*&QIo9-Z8Ya*GzSovl32r|-YV=$(nDnrO$Nwra2J>@EojV3szA1X5+ z5xm)i3mf2-Y0Zuibalkje|ywneRC*kqlSREvmIvHWOB)+U7$A=g)>NVMTmxcVYEQ;*Li7%G zNC=6wg!DT?qn0}BsQ8@}I(D9_w!P4YoaDmZ(~gYd)On&j2unbyT)R1X&j1j?e%m%a zdO**%@9U)y?DKssEiL^ePvv^Lb3keOR*se6ApWtY>h45&R>B?o3#wPa)>BmI{8{ar zHzUt+N!TBq+}**5M0Q2eeJXvx^%`^8p-s%M*}j6CNiKyMVXlLN#Nad<%(&ID;=?(D z8iyyMy}rp3w>R6M_L{WA$66f$D*i|+yQOb^YmZ`(EdZ==Of=K!EDs<3UrE>dbEjS> zKF!IVBXrhD$01OWb7K$=>F59f*PuOy;H%$RlB1P|12T4}z>6&earC?0y_;xDrQG6X zOI%+sH-2YH3{t(YAomrHaV4B;sIM3Q64K0pehB_?bK*7jk`*V;H~I8EZD$lH!7NNm z11P)bo%#JU2AR97H|H`}`<6j@=Ryf&afsA>AwG z!8LI4Kb3V=69Ctl%=QE~rR2$-?M+Od;rp*iUFj^LP3VILB6DkST{91k4n6lk#8}Ar zlHbirQO$YSRCS>S$c{?X2MY22KZ;Tm=PMTm_4TrO8_ldhOG`m{ah#MpL59S_-7hyQ zm45P|Ssg6>WHf9HyZ}WZ%BJHb=Cq4J!=e5!a~tkGAKKkelc9>gi@mogSwP0}Apw65 z?TqZ#je)9OK%5tVG?CaC(RLKDvCm;K@;WZ5sswY1I1rI!NIxd&a}#C#m=<_y+a+}~ z#+BoyrX7Fa>e%LbQ&g$WJ*Yix3E2QZ&kt^$j*+Jl8BOv1%t#gdFux^O93th;7|LDZ z{e)4StYt%uxyScU~=m0zfkOnhn&80N9)^ZnjSu|Ip4=JE%s;2+xn^@}Lf zEgazyzj|&urVL_5^o+93bZ_LNrzDQQ(^e1FNs)*tpbl3e_T;iU{q{3)OpQU$xYvA8?@FVzhyD6ya)1SyXF;1~f zu!3?_oe^$fJYp94s#GpR{DVZPqSQba1FslPOl_a46j*R?a1_T+ZxG0Vz4e3MMW>w& zY8paFWzk(sqjKs>m7foxAnm$cvK;CBzcmju+p1kXpYq(>8!f#&_p=yy!jwJDY0-g6 zcme&KsK>!5mtr(?xE^2rZXIkr*&O=kO5d4w2SIigYghW6B_W)R)0P=hG!u?G`0?i3 z$g8oeo#lyg{a)<`5R?0S9XXs^edqdtTvy}&Ax0&t=6Lp=e4MpgVpvb` z4Sb)8hhjdzeLN5mftu%OGzEV51-Ewftx#XyudhTnP5#P04Lz2^^}4(it~vwEF>7EC zv2;n^F2IsEub|>tvXi31@!B0hX!ekMoA&ZlhX|V_Wn)IpFl=dmMEwZ3BdftM zV3bR>O>d&T#o*JBf|9dQH#7+2y}P|S?ReO>i5&^w655cgYCh&aedof+7-0vnJ_Q@^ zd1}&r<6Cm-!TCDtA8E1nHIjM5Jnu}Q{$c_6&rMO6=SM`dmY_9(LHH6hEi$uP{n!zZ z;al6|r7Hi*48GhSg-Xy8)YR^&SBPFI{*iE+c2{EO?(gd85{Z>&Df?ZBPuYmj5cZ~+ z;vxt?-Cuk_eboR3*qKN~E|g@pM9!8FMl%X;Z1z3{MH|X%fdT0T-9Sj^z8;+Tkd3MGI$5>A&Nby5& z8T$pEG}AqUx+7|Gp6oQqJtAEWxI@MNHglEfb%Mg2gf6!MOf6&VQb25lu^v3z<@>#Y z6Mo_MB#&WDzitxr+?O_xavH0b;-c?+!*-O@(9n?m<6WbZHQ_)a(QCq2{?9i+kBZ-@ zi;=72&Ec?CJ<1MR_wds>kln?aA9?RM_E4&x!j^l?pkLgPG1Pqn^ekvY0+~n@SZm!l zkh8VG!w_wTlNp*9Oc*lyzJ(|Wnom~z+{7^UN}1Ay@N6!=%e_M?DR*yzZ#nK(&*tZE z2HtlWlpw~2$f8_j;a@iyz2|kw{w|~_p4YW%##}1svJtJou_Q!d8Y*sJTKI58j=?c? zm&_^dYkR^f*@b2IV=J}o8U^`FZ;Pmt8A(24WDj8+FY(mzTEE#dHBNZmZprcqFeGoQ zge^_0hF`_xTANb`Ltc~Ec~jx4>z}-LayaY4g*ZLYjb?3n2&2#e(9Mc&s%^F5&XEBV;2oj%?9at?hSLrRhUm}v?riO36E&_WcejKz`v5F+J4!=Syy%@%i|#X-7duKa-7=gYv$3Rc zDR>4vsBZZvT|b=9g5kYTdelevD9egQNCNP$p9l!dTI|$*(z`l5ni|$KO{M@YdAIp9 zM7nlM?W#*0mzPrXz}y+5rP=v2-_lpRyIAP2-;9&HwUs2!8@kxQo6&@UkIkG@^+~@& zzE`o>zA+6YgRPJ&Gv~P#!tb%o*3F!llz)yw`(gR&!Ilgw$KXyA}YA(f#@Me1#=8DW#7hK?`;Un_UwGUD^vh$1e{;jJ|b? zkl-F9=axUa0#17g_M-`ZXw3NmGrHj5FGMrJXBz$iUl`(W4&LO~YN9PdX<#Usxf z3vY&7?6rO!g~}&?yBYUMWZa(Ti?8{#Rqhc#VJGJyKX|0(^-&I?rlrlq)*M%9LsdND z{6beyAbL+?@Y(HmanjV6ahX}>n&h1a>6V}9Jm=xzmebfG)Sp7kr=J!SEXj@Acfau~ z*%lTThgt-5U-I|z;}0mrL57~iX1bEz;FSjt#UzH5N{WlOQ|U=4>LxLQyk^CFXWy1@ zJ>kCPy+FC%x=kRGyN#YoV^z1O67X9vCNQ;IFUA9e9_N-VGQ&p&t# zZ_!-F6l^v{!znAcL!qBZf52_=U5jJaQWiebg*(5Msf)nCc#!5rH|Kd zT5Ro(2P=nui=j1rEHH31iVdCv6|Yo>oe&ch%6Z((ahB*>Ea7Sy%vm9hza-?)FKk=R zjI*3YOVA`HAR12S5?MfBaEm2ETv#erSvZ28HptIQoO;l=X#R;h$^sYHbe*mao|bst zY}<}pOFL@iXCgj-OuQU;AZB~)%hrGg$_KKQSfuHRh{9g|{&_6HRi}=}qgcCo7Do3x zv14C^EsZnmdk2r6rx-m^xs%oHB~!TX7{-w(7sLJ))!18IL7;2X55MOBwB;fH0>!%O zouqgbeR=LyZ+&^khu4*#5+pS#<#+8m964WlE?Du9&q2Toe!!1KoPZxhAwTIU!)2c) z#=K_q4GK;ScK(&P{|x&$=ezo&Ep~4N(t;71L>J#H0W}&}KT;|k=bRaByg|C2^;=3V zHyZRlLrx)Gnx3X{9P!#ncB&MrOv2z5vlid`dwIXra5I=xCxMoB#?>0+n_0ZA+b2U4 zoy(DQq0i)Uhkv{5JkY)X48~Y%>GUpzK(lV%^Q zHKg;Ehvv<=-Z2q=!zQ`7_$_ zMXLpM#w0=$i)i00=e$I6&<*bP=stGBgO#5dwA$?PSwTN$%CpeExR^g7brYClzIV&m z_hY$wi%PQC@`3sstd=y-_GPL~5s^zJ>oRH*aX11YNcFc~uwaCFgV=o->yude^93_^P+Jb_u&PTk7 zBas4oJah{?JC8Ckx z4-NI>MU#u?BfXrC^Q2CkRMgR-GLU@x_HD}i!GZO`;bCS`=e*zKSBhPX<1GUjJUqO6 z=H}+Bwuky=UKt@FxL#UXznk$C*PWc4@_xw^h&E_xX+<8)PfU=0lQlHVwH+>fA})Mc zTU$$Nd-9Zml+51V{^$O_)d67hV7CV)UEJMA@087!;D6Hl6^n+f-X_iRd7vjJSdc<; zAu4A+shp# zm_m+P3Bwf}p?F6*P^wRIt?o$J=4Q}E0^4i)6Ha4N@wM#gYS1EXcLxS*XeK($R`Oiz ze`Y=EI6p7M!j#60P|;f2kDr{|Iy{eMWn-hm5Ahs(vHcrX;5Vo@u7+fD%y5^yFzUM~ z5_DIPqY@krUq&^sI<9j%pzgRkUWHY9yam@632tQmh>#&9Tj~1l%Ah@j>;ihN>#^%g zU8v;Z@yUtAXJmJ`ba`DJvzQLCVBIY}2o!DM0p{%NtaS>Zm6eskYk7I!mWrm5NdDjoWQ6{7%C87I!ujF;Y z=H};p@3hpDd3Flx*~dIMKwDs9Vrqgz%+zk+aG)?Z6R~=p3P9}n=#P0JM+k&#BagF% zMZdF&j)P!JsU;Ls8Z@#{luHChmxhj}CR~@J4s*wtrquJoq5z=|UfQFhu$G zCuvbh$-}$$-<#hz^lT)bCZMgct?dq|vBt7~fS;UH!%EJWrnT|(+kD1)&H@YZWXfCW zSLnvn@1mbZ@zAmda(vR_@$OSopt?MsQu(W7 z(BkW-<7(q>(bUY$BVuCW;MLVn=A6Q*mgi|`oX_yq!otD=qfzCKung@_YNRb3cMZ{{ z3kVc(%OB#sSG0a6*di+8hFN`dTh-))iS!-gp{%e8-@vdOAHQcl0zsRPzHvlz%2jwK zpX=IQQo$rrdv)GZk(Z#3CI*(L*4^ecw%<28MKV9~bQi*>{Wc*l$~P_RrLqQkBTWjK z@2-CiWC{+Zd>iMn#wVmNBVbM~T#4v-JzHxrtA~h|`(i~s)t@BstCo?Vuo$h0YK!)p zDGaa%E?S_K#5m*jY7vh9YhE1n2JvX`1CpDD7W}S_9!L$cs>CicL9Q=TMOT4n{daQ= zACHl&6AXrZ2!i;FepNWzDc>BvufjYcD>dKj)l7T~JVoPOJuyA*p`RM+I_f%EZ$8b< zv7EZHPB>tj?0&5Gg=f+KOIN%FmUVcMBmrGT(;1ylWE=o#bwBwhSW z_B!RwbQR>@ZE{%W3^W}`ULoSpX|X<7rk_eHe$)=l;(hfn(GWVy;v$;F@|z)${3xLP zw;`F2w9YRQ8af3}KW4wQ3xd}j+U~UIr#q8$w}g*1ld zy%QN@#Ke$XEt?%#As$VL9|7;ur&hY# z7}?XKr&+8ipT@s=QnpDO(GjCJChj1W9lKF{B1|SxK+}fQM8!zD>9P@ynh7>YQ5#wY zQHsB=Ni81rSYlaJCo2+Z$0O9}vUuV!)&GjNu{h{L%xM3&=7|O_;a)p|Y2DGpWcCyt zWm#)K*HuR-f$%*8{UEwE8SyyIx1Z1HNCQ1=*){jxn+7@)g&7n-|CWaR%}S6awXeoO zqalh`Aw70A(MQU1FZy%$%!MgAm7p85(i=V(s$X2*9Xx#UI>&_}1lPjF90O5czSnHh z9*RA7Eo(&7Ik(Zt7uo!AVY2O9hg1X$+6j@^T|op>Lr`)77dtG1`#X$>^uk}L2^ufg z{pV%t+`Vlg7r(QM3zWi~*lDR6M;cTc2xz6eBG$dg%fi~59&5*jP``vkw%jE$#`g=m zxid_HB$GBaCzp1Ec6zM9lUOK;(WJA4(0s(+4RbntIi>Nwd_&(NRY1cZfr>Dt`}~^l zj&i5DcXI;Ma?pn46?I}ZwrB*+MfJ~W92&}!HQao$m4i1B^xJy9O;L!T+(J(brCwxq z31J{FeJY~mvO%X$a_j9K`N%uxAiOpgZ>$>?T2? z*Sli6blnoRn;5RerDinN;wy14t5WOScc-2s4MFRfvh>ECNh60ut3pbBk@hh){a3>4 z@4`bJi@R>MHyL8?e#oNp%Om?BA94CxSF8G6K;WZxx1}H)%;o3FnaoH|;$@9O_VJH> zqjKUcxu3qUKzTn|>=$OWUW*8<0bE6a%)&|t1#0GItA18-mwyBq&JFQfPur@ga5J%^dY!)57m6VRV~wW;+vSYd zM7zi*(6d9rn6uM|)b}e^`b<1#xTXkN#au1tn^RpSZUuM<(fAB$6ViQIC!Yq7q_5ZI zteJmL19j^B)(oOL$DH!+&H2;<$~{D3U)kI5i*c(DGD}`YSicpv6eSo24nDz zb~SV?YZV#VM_l*dXi^&b+N2NmNr z!a`M=h*${-b(xok2{u}bMvH^28i?0;pO3##Xg+6}NuVwP5%Zy*?#ruk8sjQusl>XS-)kh?dv#W%dzM?j46e~^ zl3I$=OZQW~z&xzlDd*3QxI_USKb}?e7Ut^F%IkW6c!_*SkKC;Hh*02@Ra*N{&O2(9 z2}4>5wV*iJW!p<)Gl)QEEj=$w5QU$p&kqC??$(t^EgWjqWE!E+MXE3JY=I&v-00#3 z%uSqxLwg};+e1|NF|AvKT_DTyrUz%gAf!m})4oaUg;;|)j?^1((%~^8SzP~BNx=

WY~u0{@%86Jj&y@OYhP8(Bv(#c_4qL5#SP?e;bw6m|UY^k{` z9fsjE&%48YsPnK|ai*-lB77>35_tnD77?NvaqCNQ3~{$3y4l#><>>M!S7YzC!dwi87&y536iW=0)HV^d zUA9YTJ|u}>AAN*Y91*@-361yQIMP0g#-&oEaS>@iHy0KSU8fdKq3erOzSTwH98dU= zI~zSyDpl%p_WokNF`4&?ebmo%Hm{NG= z%a4OIY<``zKeUbFet^A;9~%Giv-<;%PT~?z@SJM-w^YvJFE@pJ@Cg0X6`8{2@}JIN z9PTy9$C&?eE~VXEP2kSOBo-&K>6+MoWG_VXIrM86VRm%Iw*{5pqNN9qihW3`+F;q6R^eN&Ulr6X2n-?@3FV4O#=Zr*c_Ymt^~dl~A52-V|nE3~a-%Xa{D}1YFRVdxS zi6kY|I3AuMIEzjSVH)|%vq&$**#qsvK;i!6lp*eKbCcEm6ZarKXs z$UvCy#f?ACTd!K-{NX#VPje`W|K?-ci$-y#JHgHq(<79}PAQi;{x?vS&fnd}DPN+d zq>AUwCzn3JQ!js&eBOi^Pqqe7CGT zn@%tF#L6UsxoZ1*lYG<;=(@o%?LpT`ST0B&sB2BpMx0MrLG{(AYd=zZoJL0sKajc3 zcKyqIU|6J-cNfnU`dAx6kpu8x-S41;TChxr9(UyF@x%)!Mo14xkh0nj@SM&kb9kZ~j z#NL$BrpA+;Qej#a%~>f*`-Zp|CC@bkJ(eGh-c@Y9#0Xa&-^5+&Z8AtVmCWOt&l5g7 z8hJj}I|T2`($nKKx}7Tp*IQ66F<2n=J+^q~Eg) zTs@&3uk;*Rq%JGIKgMrLxTMjrIy-JLNNhedUZfZlT)DUPgZvv+WvyJr@1YY?j}ubI0hQH^FHG->LAOPoMb=eh>Bf?lscP`zj*7?o8PRTH-G74jJd*%o&*=;t)Y0 zwMq3(QBTa}x1cL>!T)!h8A7gAup%E!&gQV^Pa0Dm2fOlO2D|(jj!{+!_>iR9{Qbt` zicuK@bzvO%m7!f zyL1iK!_FEmYeJ-$i=TFTPDzU(@^`1X;a1B}EtJa1?K>9zA|67gIYWPQLGMZ{{ig4b zq2;^(5Z0pMY!>ax!tqm?SFbSWikrB#XQ?XrH@<>h(@$M|@#f-B^oDd#iYr%tvsEEZ zJl{%xnfEt$@e8^tuhl3UJ~yIAq`jb3+j!fJ za}JW0;YJh9CpjTTXfdDvS4HdBc^m>aVNz3?7-*`FMIz) ztDI}(Y>0IyXUXwVeQ=FV)yZJjy)8)oG34t=q#(10Yck^fEzxjIf`LE9>u9;1)3N)# z+tISLLbJC?L-OHFz0Z*6Q?2OT!6e!%yg9;*gz$|B0X%Q5g-Hv&&!e<< z^8!3kZmOMUtQkTsVvn7jKlH-pTe0X`%Paj?TZ!&rS_3FPb^)k+YrVf^UsL(8Vjm{E z_ZA9du(Y%~9`{J+tvYihK4KcOAqcI>f8bR$W75F|CuvGBxBRQGAg(8W#gi zZiG+TZ^Bm-9%88eq}A&D0cGZK|M3bT$*QlP34QGvjc|t+(f#f;q~kK6Ii}?qRmJ=J zll2h1(VnNgdvddTZCBt~P?e@mr)e~0P&P~TJ>3y^Y_e;5Oy}_Zu>iq~ph%KZtxDH# zCj)=+Fw)uXA8)f0^;e7_`zaVzt5@Cn&JX^{zlinFT=?uF!cKH`l&L24e1!X@LWi~= zgpWX2UWJ3czEV9ak8f|rq)fJ$&RLYl27}?1dbZw*88IKyXq4C~e%FH4rH7_z#t+h% z2*?z}rtxAG7lACaWuuhy?PoXX`>}3VE9xg(LR&|N_r^3dlC3@Ln=s4w9ayzq8ixJ+ zN{~8al|DL4h;Ug~PN)sF#rO@Yw=&z1j_pjc+qzEJD z=f=~7K_7l?XBQpX$y7_pBNjK=VajV=yoX^a__A1JUVTP{EL2JB(`er_4m9Olb*x4{ zH_wyCKmYR14o%&!ujM(`Vcab%gr1EPvU*cEesgbX8Q)f;9vF=ERClmqa=)&7N2XX8XeoJA}N!Yz+sMZ$Qbz%N~AZ;oj@r^eq`w}q}FZZs+P`fo4}u_;BI zzBwmBL+;wU&H^@q*VPT#_+or9 zw)w{{?3u8-VWyHeG}OU2bbR74ySng}dNw=F@+b8u_=%i-2ZAq8g9GSYeo6bh>Xbv? z{5jsbpZZRYnqlqR7sANfQDM8UtuId($&@Z*nUBv8PWk@Qzp{NHy|Y_{erN2bZR%|- zU-nB^8@d9eEm>%Ex%;SG1q}k2&C-k8(|%~OC^{M`9y(evI$;Pi63Ge|QD5zDD4ukE zce`Be>{ed5(_eBp=#?)xGc8g*kAe1?*4HHbG7c3cM*phB)Z)z4#UpNotlOMN`8ebz zO@Wn?Bp%lykc6Sk{g^hp>MkFF${zSaNUiw?oxM-TcVY(h6drq3`9#Sj<@e4K^s z^fNx`rr=U!S(kl-;QscAhG`=4Hf2v{mgRy0T9tVDA&63PLM9A%|INPL7!xN;y3V_= zpH^d9F;o@`#*2@KdSBH{0P!PoZIbkD7HjjZF z3@7NJ{~<*MS;kl*z>08Iw-m`KYUc9MFTXkaZdkal(NrZvbXpVmus3=2Crw&WaWn*B zS~ZL^MfEi?SivYxod{#B2_2c;m?NzI$gdp;f?&ZT6NPRC&bXfsGZBW#Xf?92qcsSQASH73|ux~xa@u(f<*kf69kU?J%)*||DZf<#g#_qKPC4xpx3{-7B|G8)ijsnWq zFxWu-1@B89-E_fyDtI|>ftV$Vjn(a?iEICi(r0UolOSeD?PCn=eIsJtbTIeUT3;3bG}Y*jl`4of3L`Z1fhVyM^qz3 zok>O+)rnAk4Xoml)+p96g+>zv$5*u(5cK;DbvKI-O|!T{^pW+O1;X^M&quVQ&JTZa zrhlC;%^8>)fY7vd3!S<0$Pe)$6#*jC?slt5{ME%T1POJem9C9_0}FVOSq)(P#Sk#x{~_ zAcmFy9a~7rzIVE)^v!uU8qM`ANcNMcu+nJB8Ntlj`T#s15{*C>8X+m77Ww^C5 z{iQ7qy!RPWv%Zxx<*$$4q9<6gq)K1;giC7ofsR zMAk0T`?W};)(0*EkPUW2yZU<2>G-fe7-@;2=kNDnHY2hG$6mj(>EV z>Tb3W(Nc~386)q%bS@!#l_+GYFg$C2V`B0#ZBh@3=C>c!g+Nh9&{w+b{Ik*WgE(Y! zdkhG(XycoT_J|(Zbc?E6-u82y?e4(-s6Tn^%>KM>GWwlEp2<}?XQ2}daGttrf+o$ zq>~-)^s{!nOt^&k9?+eSNr}Ue5%~?t!sx_`_gRx4*)N!9t13{fS`WUIjU~;;s@qMa zv+EJp0es>>xl*B4VC-?GWJtLc;CLh^lRI3_qd=ysc>It)sj&-hP%?LgR1#nxe+^{S zIBi-Dqiwf?{rrfA#h@0pk=c3Ad^+sT@2C7gh^=ABW!^2?dBOdl6ZNfCYCc;v;8}41 z1HZ?gp{LK5OolH2@Q<eAV}}})f{OTE zmN)cB3n}zM_o+DZR(^2MRm~@Sr(jUPToqQ~rwSJD*SKJ}`4x4J)ZyjC)ob;b8 z_r%0Ko|f-mp_kmMmXe8RHNPUwM0DHoo^3M*TJf5d-5+s?j|h1l0Hp`23h z)|qV*?3i*9I2B0A^)c@3bu{r@O0R(2B#0i)A}uFTrTQ^VcX9Q=RoY0Mw0h1B)PNIp zvs{e_F%L$vkYDV;kdieomwwl-5WpB0in#2W^8BgZX~&i1$ZnUbLF9`3%AK=k+ls~J z&0-J~b&vyZ-|;Lv@Dh|^9UG78mL0V%q_fKv;4Ewl9t9qDXs`KS%m>uSY&NUx%z85p zv|~;ge<(2<6nTeo>s)cg=nT1&Fq2;RINp35Xf5u=^=Zeb$B27IOdqP;;}|Y*P}9C2 zw(zcyd!SEj?$P3Q(_z`zz$K>^wHftxz+T+OKoTu&G<1?V>(F)Z4q7Jr@aq1+HJFI} z*ofNm!Se-mxC7pw);HYKw*gT8cPemGrplD{;7j_Th0$iB76e5h>-*VX?frlwx<3_0 zS7VO;&)gw|D6&X@m`Q~BDdk*IA8a?^UZGtCXsgDZYz)xv9KeQO`rLQa{icQa0rS{5 zhQ?Xn9gg-kfMeFw$MksJjv~CR9gM^EcP1_v<*pIJlnu1^t7xHJB^I4m%l;dHdYA~% zLE?Wj=G*3Sq>sCh>bg-W`vkxez~yp3<7}>P`5f^!hBYr5zMCO?c+r>!{Oi!OhwDC+x zooUjYW$>4T=W0M-|G)wU2+8v>a`UAO%1{r8fpK&9sZ+%UV|0V?PhHBGp;KKPt5fgg5I}S#XiG! z7cgLFQuLd_DB!O^h7iU?Y`#m9x_5hFsG0-NqXHee)7knE_=4wytN;Zp9&BV8;oGF3 z^N$50uHblu>12enhH3={y+Sfd90DAIpGa%md~)51t1qp?`IL(p!%?vI!*^7&T$_IB zKSP3m7&MN2_(Ag`4>E+wMgs-jonjhfN20&HaK`M*YK*3e+l-7U0Zq2i}qt3*> zFjB!}labFG5g?*(j}3>V&p<(FD@XK5R=MattXIIG;HD1cT=m-XntnurrfvNKM}X zq-qBN1ohF74TgD2d-@ij57^NSe%@f-RoZ2YML}cYgPrBWs1VW6&p>I;0Pui{7S@Co zFrMq}(NfNl&0~ilUn(iUE^2~t`otLKS5$3Cg*tS}1oEb+PZHv7jlx5eKj}j6p4Q4k z3c1te>uPxLD#5HYL`MyQ41x+)(rCwr$KOm!c1wN5Zm zYMLi#IrcF@A0wXtHRaNckLeTwiEk0bh5{?tkkOt3xaTK(r<&CWx&+5ft>9Z-F=c=1 zjc;||di@M!eieBjXEmx>tb_j`R{C;|k?E(_KbOvuQ@#wKr?$&t5(oH1Npo0j=3$ zclWps_Tw>LKPG1-zAP9KAE80I(1!B5V3i+FO&I4^$?+;^%7Z(Y&Sd;g`pG_Sv1pU& zWqah+)Ir1{k$I?D+iY z-ktX&oR)d%a94(h^xwV!jPFkvew-9>_b+uHD`Q?ZY4I!AF2j!9PUmHpf zj1FK9%@81SJ(c*&By-IbK6gqtZavEV#U}Wt%SzRNz22E)>%_GAnyaKX=37F&gr1==Q5FxJP zIHgWXnD8|J8lTtDW~>T-ZO^=0LKV`_5uSMaClKwwZ!t-XpH`|FW2R(Zd(pf&@{5T- z`26+CQJAMHdW|U_+@atEE6G0_hToZh=l1+BZ}))`nQ5PYejpBtKQ@(EvXA7{hpQks zZraJ&cVje%5ER+dueWiWJDys^*!hh&;1Fucna$pompqm8Cl%7$Y&%PVI=xJ1oaAHp z?SMS&6v#s-_j^1zPvN)!aG2~k;*bwl)U;6{&+r>9@y+x(fVc~!1spBA97b{1=c~aC z+0IgMEI>?zHCU+SW+>A_77RAoKDt~4THmof?Aaw)+x%qV2paYlowGm+rPv?_WVT8< zWjX8l1WsgR7i5t?Ksv?V#Rd0=Yz1QS9emH>SZMrs9uZj~*Yi@l8bKVHNmrkAj}akc z;qZ;7|G|GIWm2Ymz0+%|ILilmV+}Ll+x|CIS^5#bDg6>z}8FIyXD>n z@BglH5s)VyIN7#3HdHufGUURbK`;nm5YsQ5IeJpHNa>d*D(jva+niW_ruClXz-B9# z0(;`-O=mk+XT4cXds?7lNbTMDL(s&V0WAB%|_#H(2$j(377CA*J9qH}AQjuh6UWv5f12ydcEzN#nQ= zxk%f}(Lq{RaOP?Jt*Lr$jT3u*Wa#(k@W%F|qMCo)dk_TIIYO z-)^{6S3D<%0$KB$%yl<0n}+!;ethyFsV8aj!yKsB-_cyxM7w{B3v0+x7VUdWl3;oz z1(Y{y1|h$(xx_l2Q?VG7L8Msz{>U4X5S^`sH53g24}p67cxADb@#;4Bggi4 zt!nCT4%cVJs9Y0igSn3adq)i>&uP{3YUfW{KYaCqM1t7Tw zHBWHm)&1C9eEjK(Nqo42Wbo%iMX-5W;Y>aEGIgp5dMBr<#KZAYZcu=`{Pq=X=?B~; za96NwyKs$x>z%%VlyBpuxb@q-+dIJxvWFZImuU?dg_F-^c~ks@G>Zo{um$Wrel=k) zZpbRYk%SOkkF#g1vei90Tf2X5QuzVuGmZ)?H0C@H)|=C4{36=%xc$AZASxxU6PKg^%RCvl$QeYsn-Zi-ENwz^@+0|UGLtLKhi zJtriO`hNQ?exF|?RT)PqHz0fc;FrHwA2+VgD+!Rw+@wRX*8kCs48bQumFNw-$?A>e z|2|y(w)5N7CoR{LaPEaQw-a{sO@|F%xn5|zf1kVb?FB~_x2#nedzq<^I>!g~^4aHCg33|pR<)4GYOn`sXzWrt1d+{tFraW#Nu}j^DbL8G5r)WJjjK=)wf5k>XT_+@% z|3yNNc9P8PCuJ2CFR+ia2mCb&0AiUvg)KS&_XiIvQlX?@8ZzuqMQQ{MR_C9otn3s0 zk4R_H&J7;ad)Lf7=prL880z;S@N)hU4b2R|`4lJW7o^Lc-W$U*u|K zF8b?Kf3^`!&HeWcAu}7`JF-EbYj0`wI5NF{3D53yh2!e9PuAXj2^4eToj{$16=r1` z0`eXF1)dnfdG+140nRmT{4TP%)2OS})E%sX_UFL=^S`%1(1}d|UW%ve^Jn&(byK*~ zjDz9+|G=#9zIoG$JXamIYT$hcK`O!zDcZ@IcjLqfnITA3M1o?X=I1sfj6TR{6ukKN zaR`u*iL>9Ge-hxI5c2O=5D0i?_>1n}_5bC^kpI2uej`)iukr zwCUZlKm2ykUDv(Kl1($|Izju32&fU-Aa$tLgWzD(b$k9h~<3Hjfd2#0(F3iI;b4lfNO-k#2L~7zx3;$nP)?_ah1e8w|bsVkv()m!8)%s z!98KmENffaNQysvf|OR6cHhV1Eo}uGfB=qMv4|6gk8~&L4sl5Zt4Erfot<4K%}f@0{Sg#- ztH>6AJoAMfb;7Cvrp^5WUA!Mqg*YE} z*T=Vr=F@s$ZFXHrjOoekUAmr5q?T+1sDXh}V5U#hU}JCHExdoodRjrpGyq|4{pOs0 zHO=v(JN5$*8P|lXy)V1P*8vXwlZ6&{#=2FzyzT~ajr-icIcIA@R`>(m<(P>WVgn;# zfQOe6lpX%mBc6YN+!|a^L*W0w?s4<*sK+Gb`qTwXND-j_el}}=Lp3{+!TGE738nfO z9jfC%JOvz=wH$Ev1OO8>0r^eYO+{!1kcDeXpX7iT`M1}Tz^^69y6IE=F>4-7O_KaK zJOfo7IZSB&K`NY3sZx(z;x(Isi1p+sZ)YVC)^G%zqg-8(;>nMNf6dNZ45E@EStx)9 zNLYc=GdEqPMO$Umz|toNPIVpyRsa}OZka5|mZ0XB{z)hcZnMUwN8O$Lh!!S;iny^U z6%`H#?hQo6bUQ#U4u6{fJ+LiZxL;@c{k>BB@Un^xtC@T;tL^Q6!vwKKMIRa#IEec(6x(F=EGDnh*}d`wr`UG10@(y*BHduFGvU8)>FB0PCb`WC{N0zII*Zmy zL_y@?)l!T5BO!Zy&rPw}W9)cLX>e>)4s_}sO=2S=iYhmSY7xRAp4mq&A~X+1*^#g038FAwlSOr9>c#biHhh+ z#^-%$imr@$rf@%K*aF~N&pU$x^${%e_*_ka_b;VemLDWhk~{Y^RIKh+&U!GBIZpQ5 zX;_Q3wuO+z>z!~snJzZ%L@IH;vZvIyeLp6_@m~elFvas%y!h&o#oBhqH=aiF|KI48 z5cF2`Gr*Ugs`|1V>#M08jDOFMgdh3XG*A;k(H7Yre!Tc*J%$xOhhUOm?gEG-d0>aq z5ad_-9AZ6rwj&B?HDHj6%pW=Jn6$s~itwve%2E*;wD|!5>Q$H|92PP=iIRtM0d@hF zZBmp7CSdY1KQ{lee|z&Z_#0rJ^QrME;cug$AI4{&)V?VQxH*j%?_*sHLha%}6}aVR zj^+J}(ofPuq zLm;wCgtg+IpHC&9fRt`hif#EHD(Gb|@VJvzS4-vZPZT0C|APKjaVou(qSz-Vsbq`B zTtHuv6141;%F*=K#2G-1C!3@u3J-d0D>Hu$1admWv^MOvG-yxss$Uq96IZ$wG~y{p zu1iKiuA&~0$thQ2bQ_~&QRM(uCIfxo!%mvtpNV|)C9+%Vcp>zM$I)mjj1M-Cu4-kw z0Y8y_9XDOqDiS$A9m`5aDl@B2BH}q#0Mzr}{L>u#`t?kMBQK@!oP_V=3h5ZHuA-LoGvrY6^qp3i`jnohF=2JtZJ)`Z7`E$)j#`c}l*$tvSI+vpt%rB~(B7mxw=m zO2Q^3t(ykVXnUX44V=;ctsA8I*oZf4joue`o?e9U(uFYgfLY@maRu7kTgc>lM>1|> z#rEK>@xWj)ya8HSUJ*8#i)q~pa72x1nRnz=bO+F^x}+FLk?tM``MYWEQ*6CNhlSp< z3{po(v83D_*l2l5u=DPv`M%5ygaA92KG8n%mVBQlBC^|$1F~gjnaJ_9)zLqOovNi1 zVLk}5j3B*qzU=&GOo!e1o-0-4da3jimYIDnHmr~5XC?bf@yht?nP*_@l+~5p%YU7*gWW_ z1OT3R`W!kuWh;=$wE$KEE@K$y6o~w0_ttfxQ4KH&FtYbwOn6P+Fi{0dIoXeGwN9^; zy~e*{tbO|&IY5UqpHLZ)XNiSx36B3_@#m4E5JmhV1BNwm97HBgXxIWH+`FZ_XwaN6 z$INi1|7?rzKMTR=DjgfkAlFT`2LQtL-*xf=3PAwM(MN+A9}ZQBDf=PHk6uAvWc>{s zH}}(ErfU_|SqiaWmtuFy{x>P!r38sRf7Op^UcIm_UF}py1*V1*s$97T)8hi96*<7T1Ho%aQ1PKTRZLhmjM- z(FZr`S-Jo;LnZAJb&{0OM6vH?NH%L_#l_KkVuK?{5l*Y*3}W*K(X&p_JD}JVlMpFB zVA~2v>p4T-c(sMRJ^p}b+23+^{+BTxY2Yn=R~^tERZkaCARc^8w?Ql4rk2LilQq}k z{*mo(uNh>Fx2qh<;Xx3}_9A>|BC0cs)u}HILC%jxL=SiV#%VgvBJr6V7kufrtmhNa zr%_y!w6;0h1O~{gZ#`9mhk%oA2M_-&hFTewU%t_9Ea8!`jxU+h@~8|hIbwWhOD)A2 z0MpVPT4T3iE%S1c@LBZ)VWk^c;UX-{|2b>b&b8lEq%&E zJ~um9n^->}6)^rq>(BpHob?oaIC!)B-`tG8MIQ&NMBI>wik>pD3cd<4s=)c()e)~^ z5VDs*CqXE|P&nQAR$Y2*Hx;@YwSxZ++GGn@65q=PcMORPLJDNn?;u4m;4E?FO}Ha_ z_jw5X0v;7o;gS}l7cwau|6z|^OVIuY-6WoyYx|pv*WZO_qkmze@4gruXz%`HztmEP z-|6Q9*$9DtrCk@iB=`k1O)7xzhMooq&5I(ZU7rEfh;NipS^& z`|Mp}e6(4*uba96TAxLqkjtoEk!oA|M6>S}zZdZLqcf=cvQAav-)aWwGg;tj$HvS7 zrkFz@C+Aa(ukFW~pNKfWCeQh+BEf&AaQvasXQ2B;jZoOZ~6p7esZUP1W& z@7DTF&8f?hJK@$1k4>&*E^E!12D@JR653RODI0MA+`o5f&ZMTK6iWMFvIz@62a18j zlmqW!(!j?lqL%cIUO@uRT{{0jGSFAarIM&pprM}gQ$)L>P2p$RQ&W%qJfswv-k>dV z0uz9*4F9?7_3?m4vNy=@!1MJ4;o%@6wJRK0#US1ZA@pjSzRk?|Km4RtwCzKGcXHOQndZ55&a^&Yzt^$f*J*v)o+ z4PPm~pcP@e&(+~?E2kGk2XWS8?BCw@0x1>67wk2?!q2XK65dfPY4jq4@s>#_A3)eI z)a8@tnYUN8Jv@g8Yo6-i4=QE)0hd7nYDs#-!^4=JgVC}l1zKAZU$4cFq3lLVe)RF2 z>$Hd4RMsp}V+m({v2%PfR{ckeL9*~U{=Y#8-K3J>Af%GvK%~c3L_v-y47cGLA-9GG z($#Jar>OvELKokbV49$qz4r`wbvwXyCMhun@;as3x*eb{?H2e%(>3O@aNV*;K!3^t z@R8Kj)Fwf?Cr_dekfNK;2X606+fV#St9M}YQ4Y5B(Y4v{8-UIgSxNNP_yKjyh3PDQYem?7V3Ni6EOut% zf#HBTvQRM)WYJ!lctIgr1;C6w*9A#zOLyRCbq{P;iF!O5J7mtbXtp%q!bgO#ar_3r z;D6ee-Qu-7t@dIf0MIr+S*@TBOhMuHH!SLvJkayR;N_m%^%Oiy^AL{dH=h_y~FNUP{S zf<(Y;H3h)j3FQ0=`$S!miHBs9;85YjKXm4sm!l=B8_&5oP;c=%Trz5F094Z0tKK@W zDULBD5Ue(7^{)D_r-1G2>LlNgm4f-`k^5eLf~0xq>D>fh9wH3XzjoZX=7_JloU?U| zf7CqCJgG0#3|iUQe=A_6$$6zmx|0bYPp7=usvh##b!7+|EU)ES4XcLx%vjOX_5QJ`gzNi_FuLD7d3%1n!5E}%(+{VEre$^~? z*@wSc8(m0v*e|Qesb^n!K5=SUi?Xb&G-XM%EBlWs0vIEDhX~2)UOK{hh0lPt$@+JW zqe>l<1|;#Wbz%GwWBA?mKi zR9=VG@L4*kIc_UTF*`Y5kyY$(NR13l@Q@i~Ak=kosi>#h51$(UON#qnJR%tY7rXL_?Mz=;(DL;di+U^?F%jJE1MS_5S;GHe&@Z5qp5}s1D(ON=w!MxfsM98K3PFN|*GTTS zSns#=;!aMgeT3rv8~pV5 zCu4~j`o`=K>kWENc@wIpQ<++dbJU0Kz%Fxkddhu=FOIR~l-S`QvqeO)ZnWSyXaLE= z^ls_)D!sSm&D(kfpjVO`k9fq%e83_JTVO+y%WtYN8e0;njnJwHUseR;WL^MWl zoF5+ubX+UR=CRU*A+ckYV1BqQpT&Q<*fa$jAO}OAJk~e`WsHq(30kL1NNS9Z*D8sm~7dLh3I(6nWo=4vhKV{6eK^8L25 zA&D6mmJGg6pUp>P$Z;a@NjNy7TS{1qW^3}wL71TgDme#rq{FJ8gVx>lQQMJ z4H=bZ2joCV+Qe>*dT-32fOal3Md8*QJC0$aw;_`Rg$cF%}gG8#0CSBTnJ9r^g9!$$yXXMFo@GXxlA52lw;YWC@V$I z&U_)GsFA`oG%I)=Q_u2)Mvg3n_tu>FTdJHobgt5%G-L?Grzz~KP+R?X_qyZK4UFx; zuGta~q3KSoJ$Q1psp%jaVFZ?*D#7qmjkx_X1seJw@ThU35LN0&%}g+WOg=vFCpZ=$ zmAeL^D5r0ifdIIVMzF{)j%yd zb3JGL9su~ee6-!DDo)UR%YLiXQdid*UWsBvOO$#7m-ZWa2f5Rbysvy1ShB<++2}W* zAf;=+5GoPqTv#^}5OA2y@7=zw+D|>vgRQ*r$bGZ>*>Zo$T+da8Ppy(@vugj9WjI{A zk>93d2w4?wf;ogQIOIwD+qC|($9!)?SE2`^qDxDoR0A`AX=}@$e-10KP7)Jx>DmTxKpwxGSB=Uf2?nox(M6O!m0-V3Qwv0c+HbO;;v5^Jh z+dWYoBb^~TU2VqDqRkBEH$VU#$>z$g$)AE)B%mEgzA9Y4JC)mAtazw?LieS4x8i#^ zXNEf4>__R{P5*Zuve>Id3(ddstYySR>0jaD^L{fod5cX!xJl78h!=eQ*z4@qifGV4 zz7c}k9u^YhJ`)4MB?rr&k^G~80mGTJN^|JfMl?i2v&H7q4h)yBJ8;q);f}h;$|Psn z*CvhE81wZ6EF+PDk8C(An`VsHJSl}n7m^PwYog!@7+GRlog(2yjlB~WE2F6Vm+|Co zX8Bd3wR!v-5}uonvYEyOwQ|2`AwasZ*&e()^v7@=6T6E)U=veva|)Kg{@H+%(x=V` z2WuZO|9~ooX?=YcEU{kY3L^=I`ui8_JlU13`4Y@^S5dNVhjp3g zFMGYHd9R}BkmpBf6_>FcS3>4sgE(dd@NC*<#kVG|?Ia)?;S(}aQCY7Za#T=%%2q5j z2IMakird&6n5_fw6v;rOMRMA@bH9F6VOnxNOJAIJ0jLrxRQYKy`A<*NihJ0=b1)Hh zB?c`ZhZu9H4hY824j0&4L$c`>s3XvFGe|g$AVs~uKaxrj$tCz&Tmgj^i~_^Y^{w3wAC&lvthoQmLJ>&bMGUq1A<(u_9v-rXJz z$;!$jza6D5iJ~|DM<>|XMPU;{iU;zV7-nh4q%A^Nj-^YSR~@PKTh;@|K~CJCx@ z=7NhbEFScERP|v?ML;y3iqj2f0;~w;l+qmw72@b^07xn(oLf z@cDr9dFM_LVs#vbLYL@cWi_hOxOhY(gsu(|etjpGJw}R1L50dFqqK>~s$=Urnk)*1dK_|U1lRiuPlwiBXxR*vRA>39 z%+X??qgxUlr&C)^cUulTQ2mE6~#1JAG^@F@no94tDsk}GC!F{ZI%c+NepAfxw z5LxLusPfJSfR9d&+^&?w+S=Qp8~AbfVMd!kjKX^6-OKnvOyq{Y^Y!ec7ae4PDLsAo zjwHNtw{>Fe%FN7#6Rbj({ZX<-qR`G_r3Z#2ajlMtf6B)aTu+ zV~9j~*eDLAuADYD4iCn6PoxGy6r}8akFHv9nS7fzBjeGFCJ9{90DN>rNU$`Lpb(Wp zbZ{EFB6xbC>bY3v%ffugMT~w9INCc<(Pi+|3jnHKnt!ZEUMF{IGF-(dmNpupv3;)M;mYn;#7ZbgKER`p~H)-w>NEFN@TC2AUPupeU#gXobX6 zisH`JmQ?dZsLmUKeA6Ex8Ce*!`ZiZs}RmGzx%cp5)m{g|TL3Iana z0-ryWNiEgF--0fYMmiR-8a9A(!zYlkFjcB%Z3G3#zP^hJ18xX@pNQ<*8c>R35OJBa zpnzV{O4Z81zyaFh2+#P({+~JPA}2s9K3B+(dL=BAQEyo^JgTmr+Y>3Qu4YUpC*A#6 zWXHR|I1gR7JGUw~767g9qfvuxbLq3*sM0tL0unbn6Gh*#q1BDfX#8>rcxd{F^iy!Y zcWV3ePIeTi;kxb5@e7IpCes-G*LN7K@OCE9E$Ed|It9nB(vl7{pF)AGc#(6CNQ=iN zW{2YnjkQYBK*?xk_A|@&>(69?_a}qE{PWhn93^#HXdwWRD_jAaF?7mxEOL5!dURae zD6LeccXHi>At8{T-^0Sg_+0i4U+?}vX!SWL;<{?iR+Jy-moPv|Wl`!;j9J~@bKGNN zRMcAqxixcbeuB2+xiKIvalhD^qre9Fr$Qoc?FpWZ%Hk@sz8~b%!~#LPHIQARn#Pil zQ7ec~7ZJ@4zGf;*UZ-y;cD6vFPri)(?^2xDOt#QI85uFpt@!Vdp%1Kh<@%q)kTD2X zBN;W&f?|o;wOdpPsARpdfoz`Aa==Y8$4hm^E?dkWp{~D>XakNBE)VCepHB5_yvuUw z&x4L#uK?L?9dUsRN}(>WTYLZHeu6COf_M`q4yA}9z%y{u(E&U0Z|K14`A1K^F7r0eWU&N)K*WIw8A!%{rhxnoSTUYyPKZA^zMh>1adSuuzsI*wib@Im6ZhH zB2Q*i!DZ6QTUvnrd7bC4w2V;r;lF;gPWw@J$)^s0|mkg zV^j@+{~yZE0xGJgefI+l-JycCgrGD?Go)gW0@5Wd-Q7q?Nq38MhlG@L4hYhXGIWS^ z%-!gB>%Z>0cippC9uLDhb7G%;_I}^z{XGx%`y(=eFZ?R-+KCx7KTnNvOUzY?`km=H z`aHig>ynotq@pY$UEtpRNGiKte@6kEc`o+>_iu2JDDZZhXMgINaN!We?SUAf-j1Qn zAilkT**1UHwQY0E_7@Aa>Wa6|1gIZRxXWcQ<6jVx8+f0kJ+X~4>c+a@AIphi6O{KLG;Z`~y2^a6oVpcx;~8O}dCy_-RjR1a zY@Ka1$3oM}U`4A`R;xF+@ibRFhxXmDI7Ufe55eW|$Gp~jhU7Zkk{ss1*m|>0$#`;H zw@vEXhA-ir<{?aKUWlpEi@1#Wbp~^OH=vx^hRJ+-2sK#>3MkCU(*Yl8cWQk zmZZ*rpD)67(-4{QYYh6bK1)X)zI#Uv+YgXsqnSB)v90f1gW3}QS&@HDr-T=o7yX=JCldT_vKO6UfRwM)f z`jS_ND5PE>rpNDt9Cz{eZxjX;8>_X!`{M#oP5?_Yy+b>L}DO);yVWCGD; z7hRou|LzwSE@4PToA`%2kAs0tONzqJ&F9Baq?jPj@?@b@CXD24=LoJ$=j-!HE|cn2 zBD-`+BKt6__V8GVmzNitUwcmL({M6L(0vp4h^_WKxeiN!fWUlBHmVu6QnSa}uz+&W z+o$9EFz1tzw1MW#?}ZO_gwW??|^_Jqf5B!X>(-E1WNjeL81z?mnS1+fY4su+io0Yw3+=SV93O6@ttubh0A^G1at%4AXMM5XSPc?z^+w` z1>|Twz^isBN0H@~XMjuCTuoNB97igT2~LH7R4b{9ezV;W&4qD zD7_ZbgM&t@deNAO(E&^-l!0{1>ue=N(CvWEbSSxFyYdkvmPPr&V|O!j|Fm<4zi%Jv z9GcD(u^cWR{yd=xA)C>e&BJuHSPEVfp6gPL!_`o`NjDUy5l6J~47WT-Ax6FlUCes} zJP=8|0hxF7T`n?=Lu<)AOg}f>8X* zfL{`1=&HOgU23gnzK=+1bie9_^~W-WGu_Apdny$m<~f*ol%qOW-w^TIwTq>&sb)){ z)X=-pVBl>0boJFgcL#dAcFVdCcSmRqjt4+!XJJVk*Y2POn|SxpKL?#;%_l$-s z!aU07(NEPx>_9ZCi=LgN2MTZQMxsBu#JhV%#YeCN5-LiKfo90@J^QO@@ogr zS;whcImkWwD_qM(NuC2`KT6OW&-=ZHh(*(VleyXA1#`Q3%#cja3KYZj9NvSKMyNzFoC)8=NU&5@xUuS7@lA*ZQ@Qjxj+!N&2+ zOwfn;e%65>iMAo!f%S(bp7%&EFkAbuGTgtjx5try+3I_9<*tmW{7dDRMwSQ2Co}9> zpq*Y{Uzg<>(vskUVG$=hDcdfpDRj1|pg{K9xBGQq7_qMek=7U2e)NFg+3iT`TW_dj zhy1UfW=5-6{whupGkS!3OBG9zMTKotDh`U5BbeK0CM}%@zrbh)=d7mSIs+$a3jCiD z3f-pe;@YtZ$Pl($hRkVnb9konEDm9LAD-i)oKOJn$ip2eVMzf)kf0armq+6r_sm-n znt?Yf-Bg9jLFU_~Y+(sot&kR+2}|pr9zQS^hjVs6?x)T`Rj&b=TpU5>cT{OH&P;%Z zS?El2#gTf`KuZZOs1z0(9V)iJ?;{@1v{;bF-oe9D_$lNM` zuvi6(eeor~dk?*b@@z60<}KXYkvh4|XUFpnq^UugZfEwC;MgIPx1`CB;kI85I#8}B z;2E@t^#ie^7WXx?WYo%h^v;=MErYEU_~M4X9H5WqX2V zNPyn<5;Y9{l1qHPc+}WnwmIY13islV2>^lO8Yb2rC_lNBx#!b{rzza2UP!c6G}T9{_tfn-y6|< zG3mD5L2OB1e+TI%@;_ue7pp3pa+4$>Rj?T|rcS(f0}T0JFrc30U7f(h9=eNuPO&yi zqReEmCe5x2{F>C=+Yhsc?8)e|_syv=Pqo9>R(#+&RNs+tak)|*hi8Xt>tcemTC{ay zk{u}7WDbfK@Zj5PBS&t2oHhMY1zKjuax>E#3$b#pFJC+-@;h}cx_R8~_xq zFFp2D&TI0{2~_{onZao~oTX@&j@a=CPT2aP+jm4ugw7}fe$Rd+xrB^#h((=_m7^&;bEQ+WqG_2J!ZJ1)iohT>@4e=;>clN&5(4)`5intux|qGIyuD z=keDjhhHDwJUh_<@6ABt_pyd$k&I}n91~zLJ8u^3{}S>8{|1?d*RX)u`(7II0v($W zJN$2hBKpi@H4lbbm7A7;t}X-9nj^y49M-SUZ{zS=U1DRODk8CqghG^w=m}Qv)V{*5 zABB|_d9*8v-3;$J;1fsv3`hZUr+wxfi@-~HlYL+SiEEG+$kL0_enBublp&I|U=w-b zq1Hb7?YSBnwD?Y@GceW`Fo-s?t|af_=J&@oo!#s#$v|q-@oB{@m{faa_dT2mi=s{_T}In z5pxK!9Cd{NEMLqhNtr`qBs=&f9m9uvH6uhq)cHmR8`9w(hVEymSf{ukeXfWi!`=1K z)T&cB^OfXJI0jk?PJ`3t>xBmUz`Wdt=GNd9a$Zj7n<47{xthrc=Cl4eeKd@P{g%*CB1mYHe5N5gsCZuj%C!2I`6qiwsyipf|_U zKZyh}t=<0|eX1?Mdh5m8AcRLsPbYpu0Y)=%5W8sjMZo=o#}He2xK-fq%4i_wQKqUx z3qxNKB1uQVXeH6RoGh7ejd0}Z(?tkn_V=CQDSUV$+Iu~U7-vJ1^zD4V+ergdH`@;r z6pv3&ON6tv{`p~oCM&~f<>>GE!PVc@rA9)KQYSn8EO?hq!WT@uK3q0=96$0*hSO=3 z3nyOaH!FEx7wv*W(zdehhn%dDQK|`gqGsj#;#=g5V_!<|nh7hjaQV5E7 z=Z9h3X0P*V#6;Xf#p&Hl!~I~4xj;?yAaN3c#qrCAp36d>%Bd#ca<@Nwn)Bxr=0y{R z#V&P@YD!WVu>MeE(D4jYD_`sJ3%|sVPzg5?J}vR<{?n~{b7oV7Fh$zf!=Qt(HPT&= ztw8QG(@#D}mmQ!n6W+t8SAd|+a)ZA8a3{O`oLNWU#^+fB8mP-`36$nSDNi!DlN0_L z5xA0!7v^u<6imMl$;eG2T5pGS+cVS&J(iB0Cj?vx3@RyMVGYJbtR(ibYimC z)7;{v-KVW=Z(23@Vy_(E_HWu+ChNr)Jc0Ue=_fE3y@SXQ_f# z5ve}`-XnT=1V6grNRH+MeK2=UhY+BLtRVgW^;3oOo}Qk^hXw8TcJ56iLWn9K;*r$e z>nfP90M-?+w{eqkgG<)yf(?Y|<$>W#RmwI9*^ofWb8Z9#8_K@kiC1?o)h*0!?F#e+ zt|RCxWyetxFFY0Rpr9U;UF-=24ng$8FsJ5dp~t{?aAuDLa-uhw#91&YkltV|z2zQo z3G6A%XX)H0MfTAGK4)gqc$$+!W@&}?T@N`=_8>JeEO^UjNhwYxN;oV}m2v(s{%HOK zeZS5p$w7=70KuXYk{}9ONJ-i8F;wR-t$dSe>MKrTn3?)L=ji5$*r7EM1*{wn+x!GV+N;uUbyYrM`%3tw#$l z)qmamS3LRu@P7Nh@8Z9F`v0@XWh5>{Vy<3!%K2v>{O)@QGp`lPN=iy&&e+t^^XX#`09~j@iEwu(`<@u>JzH zV7-~gHm<(cgP|WbQqF`|z3$kbhnGy3`&3lhiJceUq;Ni_qTPCf*NF;w1J9Iy&QAj3C#(EcISf($%Fs?V8B_w z*eu2eVglPxhw7l9;15Sb>L9SwA1A=MZE@i#MkD05libzQ^IPsyfVkMpL^js$SMk{@ zsW)sxJ22OiQphf>LLHPUG2Uv_KQ6I+ydSJ667Wb@_rN)_5_EA zHy8!Fb$YMH5S?oax$Gprk`kb^rXF2mAlJvUC$-)heatajZyCJ+Kl0CR@TVI82$ z{RGBSuXAOv(`#_n4-XHk!AwQ7>h1fkuC9$!5M4|FTJmKpXEAzu$=2%=?K=m+)`A_( z7^kd(QkhLYl`jU&$@+k(sa6b#r*B2cU=$beb0FcB87divjz;u0ph(349d#e@{~>3b zcmt%tjX6#-7kpA;$7gMzKF)gkM@drrWA&(`Y~$!>K`GXwK+VspR!nyJ1B)A>An#jm zNR->6Rrl`CkE6&BA65kg^>l3~ODTwLl5mjV?$D$Dy+s-jIvD?(y{~HoGxg3Tf@Ex} z&u`1#H)mU#VQ3h!sj&~>qSv)vN5@knee>=|#+kk^I5$GhynX{*O~14cJ=aIcK+HiP zVCI~0Tqo;1V?PkhOpg!Z_j^8scW3HGmpEOc(ZQq!1mMo@p2w^{SWJ0fq9vCUV5s)f z7Cmwun2pD#r?a))F~$1|G|sOR1|sgI z{+lTSluHVjR|A{gS3z&pJNA0f-eb8>@dk|3H&DS~dA;Gu1D#ec_hAEfpi39xtkzD~ z#MueIclmCj9^7&d8lXRq<7~TnjVZY72#Rf;n@croK7ePV8EXuQ*U1Hb+*;`=`I(rW zQdOJ4IrJ0{poW>{e~Q;gR|h+-DIpgnuyD2TySlrJu=GkbxPO?8WQfR0F~4p5@Eb@onJPP- zrDf@jGWW-#pF`Ee)+dTo9Dw6CO1+V%&pmSmM$gxin7SA_EpNL&n9EGl=cv?`g0Neh zU~yQ%G|cO)l0ykZOBWYH#d-zazKRahlw(W*kB)wHw}os?u9&c})^P#I;$V*ZQ8i1F zKCKFAm2r49HBi-isMq8aw*N;<@K<014M>3Xw&fZM^*4KXo9A&(`CY$FqoCMO)p-od zbC2oUzCv>2;X=p-$?v8=R7i;Mb&dd+G66hQG1nt<5UTja>Dxgz^#~w5eFAaTEidu& zpQO$aS>7ip^FY=iNI{h)EQg9VA(_Y70kKj{`qTL5 z5m!(YvUT7B49Y?4Waw=tae_FEuyUnFw8OcpMtic4fFhb(MbhlfE$IcGjyV#?!Y@!Z zCek`uH} zbUsM=(C3TR$%Tq89HNw&cE)kWFPT*naNJ9i@B4k)0NmnG#ECVlR&61hMx~#xvfRRz z>(j~exf^Jovk!GQ!yY}GKC6XBLu|xx7}@wM@&`yPRWAtgt z0i_d3XqW_rdtFkM%K(-ob(+J2X5vLOcYN`{6rRj29rql-<{p73gRcfd)m7NxCl+>Q zv7y-IP7T&#@d}X4p|phU@{JwWP3cJ^l$F1N+C3i66RXYXsyv9+4ANegTo&w_a8n|k^91X;;C}qhd}9sB>y2dm2H1uEPD1h0T$tU6 z4rMJ@?CYZ3Ly&XJHHo<@o(eJQzz{te;*I6hhv735`GHtfA|ACcpEb5+XC=gM^AG}Rr(jfntmUu7NNk1WQtY<}Z|`032vP(af{}j=+tY4O>W8PK zG#YrMNU;?|lJ#Q@V~_jK_+y6DhGef~x$tOT3Dc`hX$IIFVYV-3)f!G)-5EFll@lMo zf4#_kCotY5pGK-Edj7NGfx|1EF0t+EXFA6(FyZX1CxmUJ{?*SzcU4WYOL_evcQ(dU zW@|0-?vo@u7!7?EL7pQeta*)fwxMLatP+V*SP)$}Y>T2BI)gGT8kz=}zG5h? z2MrIuvRfY*!Ii=??A{&}UvhoJx-XRf6TUaP=`z6Sb5ZmAEKV_={mb-MujS4b@lU-+ zNYotdmuAHIOjQqp&?R{PBrQYFL_+BJ-yzlOPkJ94$3$`Amm--j6+IU3Po}cdBlS12 z*IM@L-A8iI1<5N#-Uzn@Wk-EmMl!8Ja?&d~Ewk=+jk*Im+At1X*Hj{$L@I1U>nil= zsIwGmu?>k6L-Hnz#e}0U|8t`J6{6uX+`i<3hc8I-5rTw=yVZjnNB7xB-;q4D4oArj ze9x#-!#V70%tAC!CXcXJs7BUp+3R4u_ciU+1SrDdDv3A}2D89ZhLs5+A=xif1W%tR>RYkXM9mdv zG=v%2yxlVjh|Co(M?-evT`iRg;e6F7CciCu*FO3XykrXVFJw6MLFW<$=fWo!i|b!L zN_u4cp5gQ^p7*#k`X#c2lx|$#dOSG&xMVpl3eQmL)1?_U{nsm`kEbJN|5mb5R7}H@ zgD=3VRBC2v*xT}OcG2;2r@7*!04e$NJN&mMvGhDA}$R^u~njAF$gc#zsOp*6+{4pS)%oD^D)k$22JZB!BD_L=KT$ z9*efx*w=Z6@@(HzO7xzpMQoxVYFQR~Ex-J7edPVvRZ{~?+@1M19EHnl8r$KYy@rG~ zX%W&z28grS6T5dUBiv%^LTK^mpRI1kn% znm@JSCHJM0^-IspuygV%HaUG&?sEE6U2TLcadL{Ds?NBivA=six734-`LvHNgGG-4 zkz87OVtvC+|4m*Yu^RbU|G4;(u=V^LB!YCBIjFw>vN@lq>&;Eq!`U9cyByco(i(!F z0?_D2#*Jpf(&P!f{KyrRl9&{y{1MJ!T%%K#R=n@eDp381Sv#{TD-dn<;*}>(`_fZ5 znkTc;o{DKcB+Xlll!N{g!Pj!yF!CHB7Fy@}LulUma|1*nmP{j262jp-;z+x7Z8p zR0{O;HksBGotL{l5p!nfV*?_Kl%wFb@Jn8*6Wr6V&B>rF z$)A*29XIq)MvgIUM*r`D8yqq|S`mrxCb?M9nii|Q)sZiR-j17+$`#aLz08yg zNm^N=6}39Rok}25^m^FTOpnzUz#S-M;JP@(78cm9Q6VXpiaI9^#-BC~DVY=$4p7+=ktY3-cNzZ+$blnp@SMZ>f% zmuNjUa;ncv+O!MC58f(4;-#FEv94X%XiJHtW9yMr8bOv2}*7dL+cYUC= zl*wr6e0oXMwY<_`D15uvIJP2&fDA+a&IcEL#fh~Z-Z|`m<+zkU$hh1_4Q!mmS&jk-cdz+H@#F} z_H}MkqEcA?7{(H1c;0<71^33RA*l5;kxo>?gdKAq4ZPMUmqrZ(Fve;19&7#rbrdC1 z{0r}w<+UHok2?)zS*^LH*|whh?bQOR@`Q{cDvVl|q=@3=yFEwEEZ&$t#`>g z@mR6C#uHKN2#n9KfKlj8!cg+5w>kgTboIS zI`L)AF|9V48fb7yJM|mTjppmvYGr^E=KuVTE(lz13u2vk9bEugry6V`-au#aCzLrP zRS?WUeucOIY4ndBFRAnXhgnwCQUF!^vOM&cbPYbbc1ObaY^m8+vx|5DkL!=^G=!DT zY7cf@^dt0W5g4!3GJ}nd$7cTZR71>04YPrsLqAj9SG<6ldRW|I`2NV85TDrMj)0xK zs;CAWzw208=m5zKF5!lYaGf|W+V$CDi${{KYuV|bn!0vbIw*8GKHZzvu-@fT|JR`D zda|4+HPzZfx?W`oV6XW790YXeVwX4B$o8Yymllut?ri(H$=4hlJqw(O~-4BvKMCSX(&mK6(Sy2srXW;te($fevtgYSbj ze0*qF3Zg1#7q4p?ndKl;A*Rn=#eiU!G*mcmi^Z5F0rJ;$s`Z-OR#xXF}U@IA3^7 z?KG^8K*hT7^d6CD5v5p5REd%IiB^p!{4v)?$M?yEC;_wTSYBS0QF$Sm=2Z& zP*li`YRlyP^1qxkKl=8+5l*nHzYEcS*8hR1N&KHT{{vvVg{j>xbbtT-AF=f1n_0GM{&cl|y^_DNaX>Y$o;y>SrbGz|BH(CB|LjF+$Ay>Np`{(U8U&4<)s6os$ zanR)Ax+3S_pFfv$u9=B=mPdT-Atqn;<`wV#$hXZ4H;iWrNVvns!n?ZM1sf#G=#mxx zrO-xWaHpY{w|Dp8;43d*-(D+zk$MM)T`QG;yZXd+1%j=&5!sa$`n~;q&8_RT>c>{;PQcjPGr2ZSAwk+<Av8C1KrxcE7jiL{~|pj)2_MQn65VFap_nYhTjY+lU7yC<4u zZ+`oA50u(+fNEM@7vf9Q!)HSsCb4GjkvUflH!b ztX>?Q8|y8H*WU;by7BMC51QPiTo$o1-%c8Q8r(^L#G3`TAl>#5=T0qLu;DGZh=KKq zU-?CYmZOdE{>mCq^TQ!PwEgbnpX}!WXCFDQ8`BjYc74vccjMsOqSx#Gt=vUHBc$SN zIOi;$=3Z23bj_g=6|zo7_Zqo;3z4D+SqKs==ubD%YH8U0$loIOBcGvBUl4gB zadv9Ak3G5(NA^LA{AqXc##q8+0v-tX*=5NwcN_D(c$Dys%EyNW4}+{1#ma!tFMHQX zcr&DP#X!{Ni}sa|_y`Vl2t_bpQOP77rh5R0B1-$b^{ zwZB9iNiv~{7x+EJqq4gZoO+n)_EvNW*o9OG_NM0v!s_8>bs&Uce(7|%`=!^K7YPV= z1nB7K=^`W8+r0b%I8bkL-rn8|D%wQF(j-mgZ)Q|*z~g8Dq2x90TVVWQL)DA7rJ#~k zhiX3)m{aXFtPxDo7j|6kWF2+8ha0s3g#YSN9%~ZHUuXxpc<7xwivK7m@l06NfPZd6 z7OE(``H6)?9F&1?!s6NXSpq!f*+d`&JJIu?15?P>N+c>l0ym4Y1G{=n$c1Mgdz3572O4?_ z#WLR-ny&I#ohQm(;bp9$Rn9Pac2@8^@SMsQB!D~jfe%2#E)ZDu+S_}1O{Tj>5r*dt z!9QFdx|?FyW69W2siJZvQt+B~WfNvSM5Mw);VJOALt-+zzIHf>+tHa51M-6g+gi(kpp=yduc%+tFA&CR2tVn(#4kVzE&JaRE z-DVdPQTrPJsp+a;1xVblj)j0*-50cL9|2I31R#II>_?1lDUofqqk6X%0A?WH_}3&y zvjpwmro(>&DGeUrWgt#VFAc7&vd*zqfc*7mP3|e=u0rS@)(uo>)v*(tpAaY1hUkKL z3Y(v9v_?GOZs?^Ip(XPOI>O&%n$VvRl~h%5OA8HUE$zo^SsyKXd_{N-$`T%pKJBjWRqqtDGvR%8A&t-s?wRsns**VjY)Qhbfvz zSjRhr6&@ah2DY6w?E4J$W@sz-xMBVV3jmb?J=oxe^8vJz%oa&+Px8SU97><+O+4|O zF(=FFm@(>TpzAOJ<48y^ia`p>*3_)49gBp&ziaWUU znLapFxGKW>DZNRKrL5+0J|R#|4P{-vB7;jW_w4l~>;@fjWvQX2-`?$l!*qi_+dy!@27l&wV92)(phxm2ATqn~G@QdiKwrj|5u#vw z9lIwg&iyp|tV8s?Js`w-%-7%VCCRl)HYzdoHcje*1FTB-+id8s!T^m*1IcN?1S+hh zTNBsfF#HizAdZN#{w;!n6P03sg}_&a9r2E!uNlA)iDA|U1Bf0t6(ZlhnUW_Ub)j(@yI>xPQnNOzQ> z2Q9*(Ax^sn!uLlXwgI&@Oz#A1x!u9Ic}*qysRF_Do5>*R;G)kTW%k4(kZXD}9V}$tWyd(G}an?JO`p$aderzWl-|OR*oDiB1i`U|p zGw@t9m>Q)9LluV@nZ{j9x~^j~yk&Cio6+=?EX}M;^bO+lCB`$-Ap=-PxK1To@B3uM z(Ey`w7O7p8U?`MGugOeWYQMoG!7O|S3krD|IOKHy z4ySHY{H1N`b*#L?FUZ>`_%<^H0S6ZJHP;d=`ahF+}2^F23#A_5SE_qoUClY_f}tmj$sLx})<;<>2EkM7S_ z_WhY#yn-b@`V||eQmL@|d6QnkOWh27-HvN~>!p98cHk605tM~O1!=u}fSYTmd@8nr zU8V)9d>gpw=j%FE_=)*1{opA@TXq*{6%m`#rv;vb4^sf&h+W zWGemswdl56Qt4{sg>0YrP_z?oBE0&6cjHoa-wlcTu~<tqcfpgcdNXBo*rQ@ z#3w*F{tJal{=JP<9M`Fy@2_Mg|HxcD;J(Wd&>dE_pRY}+0g*rY^-pNmuTUsfds-VHnh=hJ@3gQ?eL8=0V|Rf)O8SR zQ&f){9qD!%K}`(2uqOPHuBpfG(| zqljpEeyu|B1h)2hj0^GM0|e@F|ME4fnxCN`9uz>CGVtJ6-P6AVg-AjZs)_ z;2z|0BFQW+84tA+^-6@k6h!a|uiFMaB21+{a{YGUW#hGYOBZ_cbSFF;;|?xVnEWv! z>_f0dzMn3ckzuJxuqTMrcZYq+@=+lh2&ia%{IWQk+Z6MhKoZh5XqRvkCYEC^kSG?9 z_a-ichIj}2;$eE%licf4X;ZEWVu}heQ$+K25nRiIbQ-P$csk76qp&E=q%>HAaE`v*{iH)4Hg!rmi`mglSgS`{ z#w)p2wp5vu7D0L2*~A+Wl@U9u^my`X)9z8YbNoa=b1!q6PMcjfdC&S^@P?X7X-LxJe z1aA-2`_K2^^NzF*ee_H{J#Z-c>l5+brw4z*R>My2S!)9rQZPi2H}mwpUfCL5=uT~P zEq;A3_sSCdGGBAM67QS)J3YB|*f*g|gIxDR;C)4kgM$-`gk8Syrs(@E>lM8%y?(xC z>wg%RPdH@sR(BbcDwc0vRWFnx0$Nd^5m>ngLN)k_Odr3&W|rK<+776`xlG%vYn)MG zyKvoI=jHUK`8LX}>Fg;HCy=*Hk~iHweLwfD)7Fc!iLab2g8NsN6PnXp*_R&k zldJQiPM{O{raho4k$x%nVBT!tz64ikx$ms*ANcMobWEc2KB8r2);7VwGbWRJZGc0O zlW8L?JUCwY`N8E-iB3LF1-HRLN-i?GsM?Q`C6R$QU{@@^UD|O0TC3KT;ajTsj)EfnhS%3X-}iiSIOY-I=h~Er-21;yE(HFL zv5Lkl6&&~q<`3rMsiQ_d6>-1iS-cUDICrg=`{2*^jbV zS9JqOb14~T2$RdOYQPuCZ%cFCFgN4Z%g(*S-GEq4meipKt+HE;_90tmP0ga?zbQh+ zE|sOAMJf>=oG1%;Uy-uhW0Y zYsCl0rH-{e50A)Weshu=<>E(|HySZ!9~}fZ-=lbBTt9lS1zg{7#mFQW!h^r7dq78b z!oREY91^dm$oB79|K4V7M)m@y#pKUc6!otCPw%}KIBrqWUb^@Gf}lginX~NG6O<|b z3S+hv!zP_ylkxCsxjPFH0^^atf8TlhHsRZA?<}SFdlQYQ<6y+$8HzB)cD1 zG(31i#h$dQL5R+HxcXIDuha|Sq^cCNUs?U1>BU|ev3n6You-ZF+uxOjoxq}J=By{# z_YuSZC%pbW^ON7-E_Aoibvy??RQMJWP3jyfvs_ejksG0|rJB=i|i%u`XRR@VhpQ`Z63f}olaQQpKewf@im zhTkd#&n@URyAWBfdOGDvLEYL36j${;=eJb)gReXuW?So9_anmwpjV{CXxMnSRH2+a zR5FcNQRd5>m}eWz5yNTsu33q%szy9y)x<+Lmskpe z@3EX{JDXr8Rwv$nr~8!;yPo(D0|WA@+7;2XWv=BurOBzI{G`$e-rO&dU+%+Zo;pdY zC+DZuo+xPtT@fVHKcW805wQU=jyh?#P zW@*;Fe|SMwZI3@2l9S?^%f^AWUr_x$HQ1~M7#ZftF(EoAei^Er_f67@ke&PqxW68M zYwT1Vr8H6|5+S-ejDoEv+aYvayMuGEJe|fKcHT&Y?Z>a@^9Wuct9~xu>1*iy9T=g1 z|F;)?c+^sn{fOspghGCxSN;Jn3hLK(i;qX|t3Pf&k$A(Uw-S0CJvfOuNPK_KDb5=U zm3CByJe;0Q=5^;oo7U-lk|#u4rGD*%PoH8%Q0RH~kO#T*9Qo#!dZU^=j<;7-!=Ix0 zRSrF$-OO2E?heoU2(O!wa?!qX43Tb!xcw6Gql1V?)9^B1nD|`GnAv-mU*kGOR^z2y zJnc4V(J63t7F%Qb@Raa@kE7b@L55PiN5BSR0yn7YyKj(v%rO$^le#h5HPB<8{!pqH z*I8@cX|k*(nkz15pedg<;O^3h{0r1%<$d|3xZfn_Xo}qE_qV0UbM-Cl$(zWTDh~(| z)JfN70Gpv1Cp&Cm-n@ zhZIb?n)ajn%`llSXRuMirhlJXmqY(4TR?PWh94mka-R%2_NZq90rY`l~XqN0I#BTsK@g%$#Z~*VIi{&|16gvNTkRO01 zF&ddk{j_^{qOZ@k%<}jaOl4O5-E44u_^|2vjhOH>Z18BH?p38h?frMes>U;)Ou!+9r2Io#Yy4r_FY$b;VHg#(*}6z5k0=k_0qmxF>n% z4otPXR_Oq*%{SGBG?`M|$IDGq-V1xnaJ=q$3NrL2y5y0c)dexh5_WYJ8-B~fEzg|R zaXD=M#5E{mDDtq_;8se1now%M^*1Y zprnNlvSYY@$f!~pP^!N2mwZ`(i-WUzs-k84p%}m6WUl13e{h?ZuhI({NZu>NNXoD2 z|9;)5Zpq4VJUfT1j10*zNK*d=rai%-xBfB2{Lz@5`i%9}3wa-bfiG=&P(d%E?H5Ec zP9+a>ZfUJ6)ad9ojhmm9sK;yprs|busOZ%}XHFHH$TZC$-9*M`HiID19Z#Z*WZ4sr zTt>;z3lg#_#$vWHJAvJ#;4DP3db@k-)^n;)LR^@GB zGY1vYoDG1|L|DrbSQ1^9885Re#tYU;UP3-D(+&QH&2cKD-(sl$#-(l}SoVYvd8|E3 z#=W>Iq`&CN_RG<{F=Bo(4TwB|9q=D?hcw6W_*IdyKDzrWN~4KSH6}FL?sRBeF{B5F zypnCEbNmM$Sxyv2?pXk>_fAz+Y<3-+pPOyT$@_;wmt8hkX)ztu3>^emC^197oU0i; zG>>5MQ?4Q=G`0;!f$V7-Hs6GH}5Cj zvWyy0yN6;ZMP?FO_4OAh2dO8+CI2~V(0hXmV5|W_c_9AQz*h5yk!UVF1Lqx-1@B*?!@mbH2OJ;$_oqKkckC3csBi(;*$?`jHU&{O&$0BArwr@ja0X z9WbH6|G{^+e%Qm9{dBCsZ^=DNxrTZ--n+`$?B;&l+Qs6cXP6vuixlg&DF>Wty$yKe zRlza+o5~lO@||xC{e9+^nvnCoCjaYwsZt6Jy~+5j6F>`~pjae7=b2~PjPLp8Gv}&8 zKjE#(7}`tZ09~db?F@b-IX~M)7{gXUHmX1Lvm80xH~P#hqGJS6B}`29soO)K^W-g-`mr#R*8dxb7Y!fs(vRP3aNLZH8tI&}a6iPtacYELeyBcBx& zBQ2f@LE6RDYO>_MTw0~4m^RHJ>>xkXo`okQTtJGk z#WUQ5bF>SKS8rkwt>-z7r)zu37E6eOe@R>kHGcR`zWgJ_mf!x3t9i2%vJjLl>E7NMZ=+qJ-hljn^ z9kT{o_8qfCSL~w)3m@T0Fmbwne@Aob_g?Pu*6$1)eR2s$KV@c9>J-f638of#YbvQhuvX)#yrpXLR}Zn0MxB*_6I}>4|?& z;AUT0hwbb|#etqjOZ1=@8{18F;H??E=CyvGCavM!nWEzYehIawp^e~LuE89cbR27R zMM5u;9ag8a#!d8jJ%*17IbTS{o-CFBpn9#Y9xKGrGbZY4RNO<^ayps#N4CL4u;yTG+iOFY3HDZAAru$-qzYc-L?+c zgjN7n`HOr1+=X-gTYQac3a*3p8F6U!T97wC)2bY`12IlYK_}MK)YOV2h|k}j^}d9; zdV6~x)4E%3Wp2N-vDwkDL5&(5d7=;tl>#AA7#eEaV8k@|LU^h+VSGl-NAZg#6 z*W+u>Y5zw)dS#;0{FVMam>G{r@16U=Gi?jmjI@M|idv4cZcJ3<0%4pUupTi3?r^t6 zaMSwCfV_lcqt_PjaRXYAGp1-rQVa&5y@Mz3Fj{+Ske(}|fiM*AucKz;p4$a#1qtDU zB#iQ6Nlvx`TwFi-;+HdnjeF_4$4c}vPhd^NC>^X4l`lbC({&>yRYqO6EP)ls(dw|j zW!*P$)_TQ(yW0}H(yc%z0PT%79cO7H==-NuC0&8upDn zGoE+T{3XdpG(s*z@35qCEH{8HLy>mf&#_zbJn-vRBOs61cq<|dY_tGri__>at)I5{ z;IiPS1i)Y^yQRA*xNG(^>luNd-BQSvD;mK>H+`*x-nMpKNN!#XJ@$uP=+R3^Yzh)o zo#K;d4lg`leNjzm`gz`z)_{>x2GxH$Du!x5ErG-0Pc|nOIR$}_Ryi;ja4YOj6R?L( z>#PpOJ|JkV3O{og0NOwk!2F`mY&9g8d-mCd)kOIO5H@NQ6qbu+PzSM9)HJxsHi4Xe zMTHsS&3tQMV@1X-x9>9}*)Pn%ed2JS51Q5N0~#=01~ISnWkhCXu@m|H+Sh0*!D^G< zk3HK>7w`H~`AV){hO~>f$iSmRLUuQD71JkgGs>@4aR%=Ge8Hg-UNR31y_S<}&uoE7 zlWUjg*|`u}P)rk;4qXW}0;7p{>>m3)OxJEr9%t`dY%+*WWR{|@pN^1vBvc&;gJ2j= zT+0|b?_LkQ*F3p=31blHf?eG05w`Q0&49UQ(9E>5C)@y1{%Cj{-rc`qWROZBME6yv zgovOetzPp|GpdE60E$ z27D}f&`iDAbj7hNKm^?m#;3Y>m#_#iiDyKZ#fzDcU6}YSbQL zpd_@1WhiLsOE3+z?5aRMIIh@{96`b$J4XTmo}v$>eF-KmLHgRla-uxjdD31NotmM3 zOq7JTo6^?W>J^UxX)$f3dg}20bLQCD6$pWq-g)$L=q!3|F3STD&+8J$T2)(xPo_zv zhz+QPfO!=Ko)C*XwBKJ(6&F`Kbpml7iY+nM30a}gd37O<+d)!uC zCx6;04wyThVfvsoI4!i}M-RwPKsKls^y-zV0RUIQ~xdu;HzrZGz#qV%6QlJ@u;8f zE_Q?m;5Y*DCN*}JtXl?$dkKBQG;g)0I4I72W7wec8CA3&~ zkK4N%Kohfi-xpNvupj5H#OnorNv}*Y-)8z9??fIt6e$94# zD*MH({Te6vV?w}hnzI!_BbW)6aGtQrjUT8*D%N+ z273|k=sl33=qFxp=XqZy3_7c(M;wSSZLd*L=WT61D9}$d2fTbf{c_(GQWkaA0Jmad z3Vgg%?eK5ZQLFDoQi&^QxrblKKYwiPi_vn@z9Y}M>&i=Rs)U_GR*QQ<_WrsGU2X}S zzw&Yt%Ggbuc=-5L;EJC{pIj37hA5mor8d zB5-gF&NJaS6ASw7ml!>#8rR~+sF8w z0%vIxcZIl2l5!XfGW?>CA>HFl3qhXPN$hWjvjW*P%iFykg&c^PiQ+;=aPY2|R_Kc> znleWbs+cp!4vR*-4ZzNgeG;89zUP(SO1MB4qmIA4VsETxo|MhqenDN zrQLLVbYV&U(V+w-zg_{JrF7AExr0F2UB6$1LbD2lx))^{n67a@q$ys~%S6F1FWSWb zp_jO$aibAflx@<20*pX?LzJ3?vv{eF@O}gO>x#$z0r3EFWhk|scoX7N1H)J z`Z^h4y0`;<_ZAQtp`qWtJ!~RJr8ZL3k_TZR$^VE0Tc{+SUH)94IOuAPzUu#(X9d6( zyl+Yf>TF95##k!7eoD22cLC%TC1sD1#9J@onN1Kv2RAj(q>gqq+b!wL0obIv=c^2> z8K#z$jjoZA-k{{P^eRz+^V69L{-jN}?bOEx5;?@Mt*a(TLzF>_Du&Jx-mJsXh@8@$ zTPL+Dv!W_bi?nK-h?|u^OQgx94LLHR)eV!SKIt-2!6rDFVatu|`kqN7+QCO7@d(#; za)ZaEyyyh4rD6IHOS}VlUNFI;@c)sC%_;p$wvuRL`OU9k;6h~48S&$A*Q`(YF?$jZ zq@Q9TEGgiV>G4BAP{l?Pk3fEHZrnka`{v*79DUn!VQ7C{3AvT!zynM2XFmrKs>w*P zQ)$)}{b-+5-`yzL$e}@70_c2(|09e~k{Pm8@&vQZ#1z;RIEB%RWMf35&rYrf#C*Cw z&DG+ETvPHDX6E_O02-x+W-%nH4aHqwH6u-Efn8NJjtJTM8qzz?ZbT+-J!PFHG}Sbl zZf;tz^6C3&ll#~#;R@eM+HooJis)QmYSp&(WXh{~%VvoBc(fA>B8Fb4_&h3@sYjv7 z1Gy~%OL#s`^sa&(#Q&~gUP;y4qJS$U(WO=jgGtFJ)#vySZY@&uaXE!K=0EeF%hgO# zQ9gf!;lqr6QC@RK(d_*<_r}Zp#ptum5v5lr7Z^V8&~GKZOhHC}SBnqz5=D9(sp)zz zMtbaCU({WOvDh7{y~-tYA15FSy8A{ z!AMU}FR)xW0)9dCPY8W<+Q%=XqlG%D--|JQ&_4ue(fytsH!oa&u=|DR&qnr+*+n(g z+L7B?8+oQ@LPt26La!s_`6D1UabJOUf<;ef!%ib$ibfi8?+yn zH#^R>A_kAy@ur*r^b_*~;OpfEupkMI{{%ZALthowRO{9zwd_tVH|%%PPyT>q3t|dP zy@o%0Nb|lv(`<0DjS@Ovm1le)mpjrk>9|o2df|VME{%@ODdra8%-~iOdIY4tz1f>D z_r)PDf7WurlsMyX<7uOp_se3Pp`D|jSpS}q%VR;lqgTZG&snm+{w~@0L7R;Q`5RF9pJg^2 zyp4XK{F(n*JO3Y&DF63e^!obS##2G(?S3FqSpf#)L$^kGGldc3w{PF>x&oNgezfOo zSy|bS1F*_@1TGwEZKnpPEB#oR0BP*Gebg#q#|fPLT^br-=R8Sg9Ym&ESlCC*xm|hX>l#rG<556^|8&7&IdbRGIUXAHJ>A?tPSF_3gLC zvB;H|-pPf|yA;Gq@5({Gdco67#NS8=ngZa%rS&Kb#Ljt_g99+iPud4W-?Tk?C$X-km1=o&wIkC@zH zW2?|QVq!2q5`+0cZr^~y)xI%jUB{n zadcaHwH7(xR3G29IKM^S;oz-h;=x(rVgrh_y_HXo1ZG(?wO4H0f`j z%^V!zUC&AAYH(=R20W&?iR1r6A8dlWy)e*Qu-opjboEvny*3ZzMj)NPSW1Svlak7pW@cyui$v zI*@ZN5fRn3__E-)ahb-qZ(+MB1E$%(E!JrI=w_>@tb2^PUb2$a>7Q1die@5!|AH)6 zvg&N8lmybOA~|djue(uKDgSrA!&53!uh7sWg@*a}vJZqeOq%vn6mut6nzY$pFx>ut zrta(a#aa=zxC@P_f8N@*12&b_#73#$e`_P4z}$PsFF*2V6FCU_9XMPohg=qnj*wx4DBz|UPuL?2M*3_*@-!U@|H}NR9nNH z1tm@21y?`$zuCOSKj&k5Bng9TJzZ38c2Gb0|W{zy)DrZLj{oJtx7 z3*XJsY^B3%&ICNq4|!>V2OSHT+iz5c9}QXRUA*z;?mZQ}y>ln=zdVe2SD7L~_P>mb z$1l1Uq~9H|n0?`LJAA8om3%hMDj(BdzKuL-I(hO_tMd|s#Ny3$cY1qL66K|`e)r)SnfX?aQ>NGX+RRcm!m!F{`~KScjqfv@aT|3Uz{7LF1=68(Kc=NiET0j zOXiJb@VHyL)KQ$0$b_#3eXhw6$vZNjy08rbtnM`}P=argSH-Ek5|e%o&Z}{x7z-^g zyL7mhbwd=#M^2uoVi}>P-M+ zQjZzn6aTP2LspDpnD<~vo6D*ANg<3O=e!2^y;mQQoExV_29_~B4>20NYo9*%mC~Sv z@(lpY{{9`nQ1;e_KkXRLde z)2I{fP29+Jl_~~L^$KUJmi5J$pXznjGv%`zvvlk&)pee6tVf%m>if;)2i_r^-A|}- z05(95B=>&_7_?$pi}BLOaZ`6sJ2fnjmaIa~I7ZTn27oTb@GWBjI?X?|$9;n}y%@vW zZZBBN+QsOwTQ5hoY^(zg!MqHqj^QKknMvEgH~E&{{f@C`XKzwSNp;1Z`68OOQd3?& z+7)@9$$d5{G(P@@^-Yir|J8lHIc2GPaPO%4+6{|AsP$?{l4vVOKH2ZRjl_oyG?lz_ z^m#DjG3>U`n22K-jf;bZa4F!tzBSue1kx;)@|zVyQkce1vvjmPo2gxwK1@c7*(^j1 zBp=xT2l!`A;hrQn4@dHGtjXwYX>Og5@6^@4&HVoIlyj$nW5YX9$El3#Q;{iL5r)-| zzjs_C@yTUH5IIp)G5FNbVAF27KP~9LgeEevKnV=F!+khjjE4PF(6%rz!Z#Crqf`?< zY>5Ov#%<3ne2Zlsnhs7N%1H7@$6n{eC0HJT~B<%RYSbW+eUSZ zrMT9x4-aV&OcjF1wn&8sMH5Zx)14;ebjmwM`n*3iLOv3|U}29rEcSJAE`4*GMCt$p zx4BbkV5jQV4|5d?KTb+FSy_h=b$c5Qf_1rlgeGSwRhHLyqVpHyCn>BYeS}%BoPls*5Rt^&5xvSZ4I2oSdf6a+BX7XABSk%Z)n6zc>Ls3e|F1W zvamhn=i{!ctA;IWn+@QKSfJiT z8SvlwWdSXrRn&jz4Fg^fUjS*_w{A!pOGt(Q6`+y%l$v_B?a+K+ArbYQz`zf?d`3y1 zW@3Es@-?+Uc&&6hoeVKT*68lBtOss6dD(_%0EgXcM*eO^nQgi&4E(gat8(phkyRa^ zwM~nO!U*}Mm2sYi)8C!CwIv-z-!r9)%~fj_yqu_)f%ln1)^#O3bj4gIpqugeYHHFg zhTA0Su&MHy50g@N93Pn5kYZqn2}Mdm1)5rKuo!F7NxMfsyXE_!OTO_FTkkCjK_|t| zet~lak@Yy>N7flQF8;84Z+!~cpU>w6OnhKFUWT}|xm&_;rx%S?T``%f;F2s1xA?V)Y zpW1r>xpM=-cL|e`B~_D0wr2FG5-r87o3N#GU1HV5}RL_9-`3VdSnU0eog@ih~NJ zREib&DoKcAJM+F^AH!ZI*%OrH+ZxuZO0)U9J28z4n=u0KFvkqITR+zbpG|-0KIyQ6 z9Uk{M-w=oUZf=uGxNRKX{Xpyc5HYqcpXn*HA}fY z$PA|>teWH8(YS(X{Zc5Eb*HnJ@ZeJKKGAit;XjOuPP*kODxOrDTvo?^0YtQ_D?GV! zLkSxX)GysPhR8|?{!2h)^|=wa0y{IhFyX>oJQJm}+|3k^J*5}hL@3_u9=M~a)6IMM zbY8%)BN~O2abkW66;}flYyWf_=!x|;n63cCFL}kQ`8M`A*M~nQWk*<>HO{4u zujJs#nD&V9?YgKWCxr1beOqd<_xVqHD{EaANnJ95mt#-xp#j(le3zrCuRV+JK%$Go zFP}{d>gjBE_Ys%WI2>gUFl)?Lz%hoWVecjMhdPky4pdJQ-!n6H*c66`KHH| zB~~GB^rmsL|A`#GM zL*xeCSy(E6tl!AAl&PK&Vw6a#34o-&B&pN5Ef8E4uR&7j1OMZ8PCrT_n|5A~0L`KOszdkh9 z+P^?)!^nfXOhbqQk2?CyidiA8es%~_&X1XSjbJ#;usJ+GuP_kLr~CY&q#Q-kEuSE& zj=L);vspn9I}v%R8Z7UYTDk9TMk+-a$SItLo0!A%MCpRn`$`@ zs>MCXt2x_2Paql)bYAiCgvjGZ@AX81#LRtLK|Bpq=|c(DskiE6HN3P}RrlAXUlbEb zM-eG~B!Z5u+(*0#f{1yPy_v6FjFR*V7yLQB9>`GQD<-BdUMTo+j7I&L$9YH6vuOJx z!XH}~3hBJVq9%=P-e|eLV`wchfjL(>qDY@XZ2ZRi|J4ve&TYE>_|e?t zTH4S5I|m7M%23Gus4 zi^AN8QXh9I=Gk~5>94zp--(D&;t=w&IDrC>$=lh&nDw7cIhLwU7VWJME(66rD?cpY z(OtoN&G7Alq5FA__zsikncT^bN;7fh3Q2MP6;F98-q2^2z5Fsu)rIF^&@G_)#A-Jg zRAgR9Pk#x<&$Z&ZKle1x)+KVjJNIdvJms5v@D$!XGexz%TwaDd+44HIN=I6_m4E&^ zLb*EY#|?}V^Y?m6&}nb5Z^3W<65@i zzUgxaZ@`x$A$Zde%C_kcvw?RCJRAFm)g?l7s#O~022YyC!nL2o;JWlDx%RslQ)Q4m zF#gk*g3F>niSLd9^N%?{j)7rj#n7)XVRWwx9Thj7ug`p@?Ia-_e@^Vz;&sd8bRcrJ ztb)1KeoLvWW4az#Nrx(KX?W~)=pa4%DM}$0oQ!0|_ih^ww!Q@k!6(sEX{c86Cb3Vu zd`s|$clk!e5zApe{yRoK#Q3Bv*5FOw;M#mA*{%Lr4in9~H_oHIU)%@>0*-Roi#?R8 z@$wZT9tJ~;wz#VBZQ~G{l~f#z>XDLwL`!-3{m*6>sgQGRb}R zXU>Ms->GM}HQ`yU%CEp*WQMC~*>ojj?eOWzetW^iX%K71>DWn4^hYcd}rKs1ZGZvAP9 z>vBuup@NMY$$d)TZ#3qP_b#<^Q2p_u^LeqzI*Q}5lC@5 zi01YkBCAsQF+>D+TQIc>M|It|Mh6+@^e!gHENJ{1KMW)BRo)0!yz%s{WPDHQvHK(B zZSqR@_GN!i#kvKj@vB65Im|#~xHNZ!(U$%rMZxTVRb&yrdC3m#6|whXlmlN7h?+CZ z!U%q4bFek(%XeVpZD}w6a4bB2KLbz{HK*OB=(VNsYEA9ESILL0UgzS-$Par$o26}U zZvGsU(Z*N#6Mq(ep95`zYAqCs^(V1<2Z)s^d_%c-IG2=l-ec44e2wZSYW20VNP8xjC+p;Pnc3-&hBLFTb8*{YdaRE(24*s?&;1xPgg<;z2fF;M&bAp3@ zqzt$s|IQLVLcqn5aZ$Kj^)`vY3Q08cJ3TS-Otr3FlV&Xsap*YqzwG+Z)BOBW!`tyv zxtZPL6N(htvILil!SudqxVo@=7Jv8rpqtl|xtvkyCRYKuY!X3hHH0&WH6}154RFW?17-PeoP+Rh%v?gbj)~y<;AE zhgtQIzJ7y`apZ>wLC^9kr7r1a&hp$Nv9Oo8vq;1@s6!*-*&?NYX2NSaSK?xk;P?gV zphH!hN2$7pc&a9`m(qr4woA8(P$;tu2x zIg48?6CuV6`qt;V9085Y5|`|NuA>PQH3toyQ`u5udmdils_KJ|4ER%fBXE=ffqQK zx4E*Sk!iczV@x%7M}>~$?Tbo>Pi>z^d+4krd94=drxu=7n<$V90EjKNYS0eSgh#>~G@hVB4GKA+jBqrK=U z4$-_T7BOeUrnSd1AJ0}#qe*8EdvqwKf&F$2Dz1G=r;c4na`dQPA_k|>7tBrP11q7i zYQlH8l7gWa>q%5G8By~-R`D1jkeH5;S%wzkBD|G}Vh9{+8SL&6+v6F-;DT&A4ks;l zdl=J<=Pp*=$2HcZiSaptUy;FelVUJYl+C%ljkDXdElQVRVy1a|w@l8@Yn38Y0reF3 z-r_7pKd%#3h{(=KbqVq^u*v?%IN{dGCu?V_uA%e)OqIc1hUFtMFMuT>JDMMf?Tpvw zyVI2utVaaB&Pjb|k$hUmX&8LELyOmdV~DYkrMZh`OCPt}318QI#Y$D8iDD>g3r~5{ zQql%E70qV~^eSHD6W(!jT0@;aBmSExdt=5di%~)rAG0>I(|B?DQmpgCT#?^byj(;p z_;zA5EjQlocpeXTR(tzIJYSMTH_vmD80MWc;^`NwW zc8n~cvlOj3R_5ux%9P=4>VMwUt4;tvNnLK2FAs7=$j#?9Sh-MD@XqO7U6o#mPfoqP z{ip+^*@qLBzuaW`lsC*s2DJ<#?BKuqnVXvcpAcoR!~SFOhX2ExN=bKn`}?hWS zN5WeTeHr(9HMQ67203|oJ*ikTfhUO^x*D#obvq>aB_|89TxY-Wh6*9pUj#4oSiT61 z=jN3SXMG51MD2=q4MFq?Sq_6FS?^UHkaN6oQcvKjXq=Y~OP6R>5FNDkk-AWV=q+GEN|3b%i=ELm?;kF;`P5j=SR``j zsayGNXB_&*6|u1~Z?pL8`JW3F8#LhH*dX5l2c3O2%sN+Br|nBuRGOZ$J^?w~%S}Hb zY$2e|ErXKEQlXKmH9s&#GIBoZG3`$?Ct*@3&ss3lYBY@`I?$>1sMBe(>sazqh;(#v zd_*%z@U-`vZj)i)AfIZ&6ZDyZM=2D-1L3Nu*xH?Mt2W!wT|RL4ZTwWKe0FhfcLS5$ z23cpMlp#_T`}3vAL(6!dAgOZ^U_Wv^-v|UC_VI!jvgj@hO)LKNm+gn$cyi;?_PqbD z4a37AS`Ja9E^gOQm|yj=6XA&(=8xcWX6UNqd) z4-Z!m!A7zi%S@mI1O(0p!jI)bLwW6fJ){~rQKN^`y6EZY+5A>hYf6~|;mL&9l=bF5 z8N$1RJ$u0pUd%=Nu{K`Q0nH%X@l?8A* z<%4~%85>Sy(>ji9tXH?6zR?D`?7PKn|1#&sOp8Q1!T3}%dw+yAe;(PSIdp)FkemC9 z^|F9lLNd>b9m{H>$le1vR6Dtzr`pH+Zu5cUVZ3=L+p3B&wTKyh6ZXHQM`1#EyQzL# z9G;wX4eHdt?D=#DnpT0OGI@wBcePg;6BQ+s{`)~Z$Q(}m^XtmW%J$%$W*Y91k&YE^ zldj&=uUwLA@~B1R-y|6NQ|d+P;WFdDnyb*q`9L7u%<*_eFT$LM)_($~F>wp}swrjTFziD+KbM;BVeXxsEPH(CvLWOWms@=5;Mm= z;Y)R_jBXz$q!%Q_z_&!#qSopcek5*3?L~EbQ>}pX?oC?~b*2-k(<2TbJ}>_^Vc7@X z8E%W$E(aHh^!JEAU@K?!>S+GD9|`&AWU~91HK%QD$O46YZZH4m#rsSp;FjU@dH(l2 z{{eY}ED_k7ZU@Rg{Rl)?Z|`$$*&=n8$?UQ6Y*$7`#;~dx3mjbBMWARN`uq29^pT)k z$|-qyc`hKpxzNYaEVL7JF**6>5(Fprz<4OFq@?t53uyR70bC9|Au(}LePnu?Qb9q1 zlaG%a91jP7&ns$cK@ev%1VEEGfhi!#3YUloHL$gH+MKK^aM7y<+B{hAy3c zPe(*Wky-z=G&3_}Wo4C${j<8h9tM(;q$PQmL*3o7#L^5v>^l;qHac{iXGmQ$y2i&f zh8cB=V*UWJYFQvHl&04E*2#$%xPBV~=h2Qd^9tccAlTKF{L}eSzpUk5YHId#2M33* zA{`oC&6YMcO7`R%{M)BHU1MAV0-7Gq+LO~tsh4>u;Mo~oMZKd}q&`AlrPTG6A7?E; z>`jr==y?>)6i?^j;i2Yhlf&cV9D$$6%`kK-5>#``#82r9kRv%4B{%!@2!6+Zo(AYR z-ceI~1dElz_Je+ai$A>M=5q%R1`AjfD2{Zmb;ep5JI=&BHEnC!;YS=qOG7+U7`w}F z%EeL$y@K`U+9OX4rg$m4#MRVXkcp0dQ?`^w6gU9}c!-1dI^_QA)z$_njH+tOsPDy+ zcb@S_Nf!3xZKSjaj{q|vdZwa$Cs0F1>iv}~wXtUB_Z;)I67zcua;*d5 zs69^_g(pKxm>2XMhXV)l%ISmr(FPQ%sg0MN)z)}^J`Hh$Pqr_}cD;38H4!HCEWSfj$&*5 zdZV8Bu8Mb&%B!-fm2ejoof6&Uf&Q7{IzGg+%jWIx8&)8&HpkuhBd6!&&UoCer-;#j z2IGg8T`7Rs`3uhqP=@|>aHb;*p8(mCA^;C{0`YTqQV)nYWf_>;kDcUu0gFV_O+S#1 z;I{|^87S})ms5fv!I`ZBGfNT~4L=OYur8^MVCqj-R}D+Xf9M1N10TqA(+N%T=D4|137}YgKx@;yN2!QVgxtrk7pBD6Bi=V`2kq1 z2DmjuxbsXOnY}b%JDGJaVIqI(yuIn?1xDa>yWU6a*A?Uu-0$baw15%b>vhcEr-u@6 zCoA(1*cjJqxtWY-zK?e@={w2q+VbC~A)kxgCji`Ke~(K*bMFX<-OpgJ0{dF`-%oj;s9w@r z8Iempb5~P~-)cr(Z?8qSAY1?dd-sNGQ&$oL9JWB*)fS4?e*J#$rk_x&M>xPbG<2y4 z$3cIjtO6zI!&lf^)>ZM*d_c#e=9Ywf?t%!Zl}iY>X+K5DS2M2%4<2}>d^Ttc(sf0C zceK1O=v0^)Q46%gt$@F$6Bs@WpS0VHFuffsrs{!8xmmeum8 z(C{BL80a<{3-;45VCnao4hr!Z^-gs&8fY^4rapHo(QjVMN!`rL&5)QrMqsM`G2-(- z5su$zkO^3!mV+>F1G`^(EQ@wWFKNoI`!tqRw{MAW$`s~iQK?*v{gIJ?ath(C1_lN? zEyurpsjzbZcYO?GjcABKa|ln0N{>c7AjNXJjjuW!7ozV4V8ru=g9cuz=M}u0&Pg<6 zGI+ZhcQ}I(*jn_X{XKyn=w)JM;l3^WX)(L5Wzuj)I^mO3_V;f-19_GvQ87J?!o(=i zYnR(B?M!(sa=6|dQK3s%OdP$vz5JTu+Rcck{}dM{@eqx!r(=`7j4legu|%_IyCAoD z8BD?)vdMr^x;G!6e*)YLzmI#Nu1<1!^PV|$IJ2Y!R=~ItPC)MkaLMI#f?ZtE zCHuHg&q-kz!5vWdBI4!uE84}D%%&lW+%kst*{v&|%S9qO+}Yc`w*yy_v|N@K>_@3G z#FuEESbWTcq2XM|!WwrBaF;x9$mZ*RmePZE;x6DM(d3f3V8`C0#j*9Z6?owDfLJus zY0|vCn35k3;k~5)pcWsXG0DdG?1s`Gev2~ZM z`eP{!ByOS2w_=$k)R){Bu_R&uIY-Cqg?eYyehH|+!iDa#FL$qPGT-3S3FqFG&{6OF$ zlX%ka8vxxq-FbF%GerpFuRARIuKe3>HKElEAncXC++mo^Ov8jh{D4*24UE)HmRF~3 zM7A%8T=G^JH(yTz8)hzdz;c3JRym%}s}(%7dRr&3CS3O;Fy`j?nDRgqaOl-COLv@Z z7HRRar_HCILkqFaE;$3+lvxgtoMnH1KShCWhDT#Fz}8pFkBQ# zh;6B?At4WP`Ff!vyzz}UK=3;OGuJxdA+RP}b@X|wL>KrK1E0w7df~J%v&<)_d2{{; zE{#=%=|HPt$g8_}7n=fvvF3RFx`tP6DFW6$@gMS0e_eq8Q#%u#U!sK;;wSOClIghm z&i`eV4)0G&ZQKOjiNup}D< zpR6!Fj=<^US$mLiaeQFq<7ig`COtTt^cQ7shv}4f9|r^bpm89`+e2AqCb7#T*G9dM z3>G#LX~ISKYUuXy5sg>>@J!jU5e#fvh3{tMLs8mK@HzGcNva?8X*Vj;2n6?M25o-7)B9#wegzZahdksK-d#~q6KV)KI zDnt{X$|;xL(x*y$2YjV*2&3zwT@aKZl1kXI3_aD)n`8<(+ZjZd2tyg4p7Ok`7WnQWd*SG$YRug6jpO05(jQkhzV zFD|qWXJitz?82To3clg>d4d2V^9xC>0DGYW;)Oj#?gAC(Wl7qNGVVeCHfrxn+gRM~ zk!Vt)Q6UCw*(jC0%t*YwkqXNRB~cI4y#=iSR<43bt%UvZ->t)jae4R2uZ(1FP|M@S} z`5I64<*TE#yk?Ct#tF#pU!#A%KEZ%J6WDVR${#R1LY{DkY0VNLwcaJLm1kwOT3fGD z!G!kmmOz`GLB*aDsSa}EFyWUz$TG}u*PytHP8X~er@--lY*7)qVzYUR)(3wsnQt~Kwvcb!*SvEEGI_ncz-zl4@BWdpeGGQc51fBC zE&psFK%5!uqa}X$^;029d=a!(b2$W3h+7pnf+Pp2@0x%eTeU z_xZuo6y1k`aD}V{|8w+zmWMw7?q(|f`{eIR@IO?=e-~{3U%O)e`!WCjyJ&DG00S!K zz5;Nt(GADr3r~QW(=B-&);1qA|32xrMSSzzna3Xwk;Ib>Z^^T<{i6NeOS#^`zGW^n zL$dFIs3t4f-RQ2mnRlSJ=Q6=^(Z_C;CQ{m*=UyJbP^uT?0lb-0{lu2jj?t-yh*G02 zLjQ5Mp0b}5fX&sTmEk@R>>JE^s&d)+`OE=OKZb`dWqoC(^f5k5 z>pqsH;+LJRtu>&*tc@ZBU%<@4@%q`b!1D6)q}09B zTR|OzgSXghZ~r;m-TgE(qmzFxgg$A6H~3g439fo4hHp$o1aC#VBH`fRAVw5YmYbUk zZ)t952&mH5)n!aeMb6C5+9@T`Qy+)yot&JIWc*}mUR*TVUzvC?o%r?Z*T*=BKo1QX z2!i9mgXLEjOvip{Ak+OG4lJjS_l$}w6wBfO(NRb+FD;*3(Y4Au|>RwM73Bog4`;dyIp%utwla-ZkP6LWWWEkLuiu(D#<(bv|8vT|?)SIhPf zkB;UP7Z>Y4e$0Nrz0%qWJ(EGN$43VS6b|2EydfZ_FWKJS)~_rqDKVl9I2|5Vp-60` z^R^qGoNSfFvz;Vyba2q`58!V`j*o{#khXh9+&m5xHi-iF9VkSg`vNV;sG{P)z`#8U z3T3cPP=EcpE#)717S7Jgx0o#y2Nzd5J7p9Svc?d2>-zy@vtTEMy_?%Tsm0jX+Z}On zabGSkJxq*^JuK+kd2<$cSvL8bd0Y2xckPA{5NFRLMsX8L~26-;pC4fR}&b;c{s2M$HgL;IVaLo^R0uE5= zo&X>{;f;dGBr`d?HeAE|_d!OjV!%mCh+=~%;6nptK1BgQzM81DrS}!a@;ni8*@cfb zxa=AFdEs3GU$3x;^PHTVa`%&MF4z4fv~O35WCV?X-Pg`8&dz+b0z(eJ8|52HnIbyG zJCO$4K&BR7BH)`BAQg^>>xaPG=i7qQKZu3cbCK77hRqMy&b9b{W8epCyNKW8MLF)V<$~oP2Y=ziV*z`9

O(I91o~UUOHR^2TXOZRDPkt*6<7i%o z?KCxrja9@_br23Q+663x>x&-$Mp|3T2K4b8%7)6p*#d zy3um?e=3sUE<`qV=XTc5l6&`h0XMD>39PqUlB4g&pN{xqW&=HqJE%B@JWD*J*G|X^ zicJV`6T34K36)%UgCaaiJa75&4yVd0Vww3$9y*n{W8Dtf9fkOzr*tML?+qJE6J4ig zQg(Ro+J2h`Ak_SEZ6r4lkn{Ui`4XE6B$84~cPJMS7Kb7+;!0^XL<{weuo*R_q%ThI z5Z$9S)h|oByC)0So1V=m zi3Y-74t$K({0IU?Y*bHP%EvO~8Q~29J!V4jW-=&GJ@tZ95jKo7WxRi(>w$ZQvoK30 z;9g0OUV-b5|7$O~@DSAB>&wjozoJaUI?73C<$Uv^Q!QSs-E7AQSr`^YE!x2dziWe5+09Y77bCxiiy2AW=j{(|EGO$L1Gw?Ped zLSWADdi$&IjlB)MthO#c5AvAakVN8N0!KGyt!k^#h+T`2aaMEVQj&Z? zS{}HT;cYxIX|DLNm(nsAo_VS$cCz^z+pD<-uH6?=LuPq?&aKzkbh_C$OI`|pKUINr zZo0M#E9^57Il;8@9fuHiPVASC5et1wKX_rulf#{0Tf!`%-_httkH{3QL6l-}1%K)d zBV~~|%oO!*;#Sp!kx4|;h??4b)#NCftu2dMchzlh`OE|{KvJe~O&yrI3*k{Gy>1Co zh!IF+)ifMD+xs?S8flI=KSWu z|FoyT5B6R^(YNvAdEbSQwkzpmz5%jxQxPLJ&+VjB<1vsqf{}7+Ei_;;5PcuQPdm zSmSu6-kIyC$rqU%S1@z16-dDV`s1zc(68GncR$hj6u~}gwZQKU#?m^@<7FH(Fg_C5v}xK(88U<+?+_=rSPEHC;7(1XLz&5_#COYm~N#WZ4$?-NRz8 zem7$gX)ym~JzT8V@5fypUfz6t<s4UnFwD)j#*fnjbZz+GzSjr$jymHtVR*);O|mWfy%s{(jnA_Eqwc;gfX1gwq%8 zPM}v2yQy3Io;H<2!GK;X117J*$ms9GDmZ-sr#|>$^X}cKF<&SA9?62Z2C~_^dDC&? zPrHMJfIF38?TIQ8MegnQfj(_Oo`G&^=F%UB&<@o+f#VwWnCK)$2`%2h#FXce4_w&s5LmobWobtIR| z+C`V8%>x04ULd=He|c;YJy`rR+5p&Y+M2ezZ*Vm`8UhhtC@nKpT7@H?g+{nLmR+Gz zj6{`hKAwF$#i&1!bXOlFhf=Zz0^+v5f*;>zm|=r=nKO}?lgZY-uFR1zYmkfK^ zqD$QK!N&QFitL@Hn-NrIccz@~t#~1{9P__FEuOkk$m~bGuDGvdxur7bg{+#z)-MT> zB$EvldemcP@JZ^y#~9Re)4C>qZ!G07NJQUwxu-jcoK8bdI&?n{|H|=_F*37Evd-l8 zbLR9Gl|?mg0=wVEDw5{G-VXUmslU9n)m2bVPOi(#OpXt`Wf>~1)?Plb{wWn-pc)z| zU*U!Pq|@}(D|S-0SFLAH@>ZNfLV zg;r{|=HRC&$i7#TrfWU#LsUTMOR3O($B-13ywI=1%$kF4PO*oTr81%Y0qWPa&qR;) z@~7F(_5^)mKd{EwF`KRy%4`%2PQ-tdk2^`?nwW4qPB!Cl7%xo{cm3JJ#KIw}m#s}A zC&{q&5+BN(z_Rk`r?On!gD3xsy0;F>s_nx?9~z_)lp5q2|b9 z?sqaB9G-i3F)sH^gGQbPu5EKeu==u4LEx(mGY!WWWj88>9Hz}aB*lDZ|65H&+c{e+eZKQ~{~?F|Z!Eb=x3X zjxz>-Dh46c;1Mwfz#@vMkjNnks-%8`Gnoq{B|zeSi0XE28stJt9=JGK06W9$&B%M8 z5+1Z?I#p5(1kXVbsdWMbU*7imB#%=?W)HZ?LMm z0lA$n2OZC=>>BeKN=AD65pX)5f}fWZrBg`C!W6w7xd>cB?H?YV0_NY@uWmB4^`1y| zpf6sPT4A@P=mEm;qg}u#tO9f(cr`#n{G$CL+;Kj)>Q6?Q9C-W?HbA@s$Uf}YeOqOt zX@LbC4H$m%0F_KWs7(bQIkmy*sN@N=`u2~fI^!U8`=B)9urv0<=eG>L{o%YCYtylB zjzV${I3v4VSkTA6Nn-*&ZE>K(X+A%kg0&5VeYJrAnelM9yAmCu`!KME3qiifbg`)( zSk{lH_+gGg%bhkCKMsU}POmA*YAw2-49d_ZJVpe0P}9>hP_`W61~g2bP0}6<12yPU zA2_4}z+MmtG(y7VG_v^ZUQhq_wKPd~>-|}2!}+Y41IPmw0=`4+(^e4QUKOx< zs5XB?;d>6^S*Z_XsN#S<#ssLCkZpq!tk>X#5e{yB4M=~-D> zrLNt^Ta1YKKCtWeU}=G(uHDJvWFwr;9xpno+Z!NoPSOqi9p6gN$jE3&=dAJ_&;zZh zfhfI*m(!Bai?(6n3n$rcKqBUchm+bj8A|h|mIV~wZKqi;HjRc#qM_yMgH$k(^BQ zZJo8{aus_s4Gw!!Bh7j5o-cz&!y_;A z#hRrj1Z`dcC=>p{(MgIu{lM0PTpxRKhP7Kav0X?sQj1}!hZAIJzQ${D&Q2h5IT7Kr z^yv*h$^3;%z3m3_y`amAL>HLUyT8REQ=Iq9yEDU0{t(BBp^$@Jin2|!p?eSFY~S3! z^FY|y0JvAQqUd06M6^!{PquHV!i6||_gIEcdZ@y;!K4m}5(XuZU;5%%S>+M--oAlx zrh9S-*qiEx9Imy#Z-G#|BPIDnTCMPTBj`1oLy(jCnAQ3i9qf}qulI5Jui<}%HJP7fHbOaJuFQb2gEPEZo9og#9Vb(n ze%y8d2u+khozyXGi*^j3)LQQBGgqw@4~+dK+kR#i_Vphg&CX?e(C!`&QU58tIzaoz zZ8Sv8ic2hh7q8kV6m6=J(=u1Jtp)^5OVU3|FED0obI zW7%?LnD`XQ61?BadD9cIeNLoJl2fOdbWkQcZs3#I{2>3yyXdU9uVm9p8oqq-y{r%L_hp%9eM|>I4QO!P);Wd3k4kA!9P5Nw`MJ3-*gkrRV;;5wcdeD0H?puuXQ|XO3rpGF zntk1YD77R@gR;J$n2u8FlvTTl@A}ncT|XB8^pQxBR^ucJgpBU;58z3r_2H=X_FKgm zI|`Kk4SdUmxwJ5TZ_kk_e(Yrn)+zqHqvGv*VePGqR=-n8mvke-eFalt?`E6TcA|&Z zffPL)UH@GF_qqRP>HYIf?|;tnhnt7P`rqpxLdA!hKPJLI-~F?Z{_~|*20Ww;n4^Gf zMgj;YjROt{`wUQ^UwY=Scx$)MI5^*`kj!HO_*~SRoXZ^#=kxz?F+hM~n0lpQD9C-5 z0*{}Omshnl7r2X;!u`ohjF_hjAWDw|S$>f!Dr2$GpbVDEvq;R>(R4~GzyKKsly@Fi z8}UeZFE6UYg?`JJFL^;dPHVXyPIVCK$!ulTs2Oi^IeB=aj8pXaUv3dd1lfyzV<9&O z7kr}9flYKSY(Lw4;Leu)FbhDeLLCG|Je2^)gnW~pFerEdVhlJBZ;k?47ApcAb0Xu_ z7IP|A&1Wj^0Zf*pD55}nLm`1p9Q6qkUmoVheFQ&X^qy8JdcWe4E%J4B=FwVL=ueQ* zt+rW{iv5GZ1Ganyh;bAGT$L*@G4$-+8m_=EAOHFS>1^kxbblQ4Tbus={-3}oSra}4 zE5M;*#mUR*OfZhORWAyB6yi515H^7yJ_c6z_1m66C9wKNXn4a^Rh4}^s;7okU-Px?LPn8SrsI64VOXy+~3-i`A(MS$z7t*IjPH zFCa7XSte;Sz1yPM6)d1(mUlBh@f%4Ue8~|le?LR5yt?fxa<8(=m#X+}iK2%|lo*3! zu(~&J|MDVZV*cc6esJrgZeFK!Dp68Ng|*xG^*8--&SsF4ne-4z$2M+fLtC#p`l`g3 zrlQj$Od5V@FCe*`=z4MEQFJioB}6J+ziG_1izC95hy0!;zWmUfXYcUBZQu&SRYc$^ z4~n~LVJwvM*Z`8BwCpV8SUblI>q%}kpLU>?$T*$M1egRK6R-|Nh@7aG#in2SGn->Y zJc@&I{snX+lshh6V4DS>{W#$03w4?5Yt}A}kYDuESQe_2&(x9+X_-41aGPRyo01aj zu@^YyC+Zz!MBIrvjD4}jI<*%&v@9+PqxcQhx%@q~>i5tPufDaS|P)30iA^t^ngbEDRABUg4!^rs%f148e9Y=f9Y2rG^&qV)bvK^A?G z7~~WU0S6u)M_78;!NVV+#OrL7L|t%mVCV>$ujSkq&>B|#|TX~+~ROPyFmt0_8G%0rFV9^b7n*SxZ-mU1_# z^MmQF4G1UzBGovR>0F$+u`_goRW%Fg@<&f*AwAYPG{N}99r*9_W?dJhM ztBN;ih2rEZX!+)8E_$f4kHVAL5bcjakC-&;%7(6rDu*goUZ-Oon0R*K40n5geQ$E4 zQrRd`!&ov@(F35XcIQ>x{^LA&?LN*ad@X%}_m$UncwRV(6yf@x(>H@X?pdfdjAdK{Nz(~ zN!A5mSDh-}HM;>f$Mf%y$y5Dw;zzaIAX{4?`=(7iiNF}c?xd0vU8+mR5= z0@OmG8EoKlSAOz{8jG5l9K?*L%ZT_deZzfZZnkwBjBf9kB7iSz96r+!{YkX zI3(%kEO`!!SW|3w^K%<87^KFrmD-)d@Y*kGlBptDg3+k*CLyv8-cvO3ns21Sh}C94 z01-`xlu2nne7B;;FBz0yTedP+u4`?4KiSe+G#=DA=ylK{|6&7_9u0}V0DN-X28)pA z$=?+oxL9OT*IEs1R-ZWQL;O@qUFJFsxFs}6j0A(u86cv~*qWqqjOw5Kme3%>jT<*iPh3a3UZlw9Xoh*W4r^XczKDZ+ z5nF$)?P%|zWJQ>6q!*GV>ohv<*7fsNq$`sEH5KU)Z@8WDC&8es(Up;3Z=WGzsF8a` z_XDtJR_D*2Cyah4Un&U;BM}mzFClH3rG6?C8zltXIwV_q>u?#Hf$4 z{Ep)Lo+>rK06o*}L75!nu3pk;wJ97mf~@A#5xQK2Rr=$5OM4;^$Y(s8f~yY};I@YiNt%M?dji3UR@Y zFfXnxDBQ7|PnT7IZ8M(VZgc$QCScheHt0hz zpj4yxOG_V1z1!lY>tgjoI`U}m7QoO$@@V8K&m;J)#7c8tHvJjvjESx=5{(B^ilnmz z0nY{n9XU7xzarQ~E zGNlZK?K3%11$+?6p8?&*%e+1cDK%#cTuFvd8-QRtL#BWe!)1t%Rr`zgU?5lr*4 z0M=z(;_@PSa-t!!Uz{05Nh*kFTwS@@Ex1qm8{Ud^n>FX)**~&Nn8J@n51ck;LmWvr z5?@oJnxgOiiC*WVVW+(3yv?AtY*XX6j~Log{grA?-GpurhKF{$a66bMr*(k$!4e2$ zf{EE?H;%|5cN|qAoK{hdW|ShN!`WM=c={2jR`X6c1pNBf25{g`_8Si##~ zm(qc7xNk{ofuUbmyy>Z2O?~^GMWAG`-r1JggX(9|_yEE*Q(el46lls-#p4*bik(qJ ziz&2vbl(~3`8WC#U+u;4k(4S2qHM)_-1Jeb^SO9g>P!a8YyT|NhwgoaN!q%l8E;bb zF1O*N&h70M@}spmxoPC{pG?5R5MEOnM9vUAcG&PSCiD=PcLbDFh9YmCbKl!#q5LtNJ>Dqrpy~V18Kx;>h@oG(tFtyo)>$-$e1*F4F0j1I*4&(3h9!F;boWtv{@@F1_ zn&iY^J4E#kq9?^f7>C&TgMEk;7yrZDZ3%zNdAWRTS}z@XL3?Z_McS_2MgE0KNSokY zTd4u2U6xz54|xRZdv_piHLhD;AuZCL4BB^7cUpVq@O8B*N3AaRqqdWc;E*QBujns<2zMVhI^EfTv*NNDMg() zQQSpWyz{+Q{P|P0%Fn1z3B#8-BG`G@B^bJY@=$$mHm{owhzwM?m@X>MU%n%|Um@Eq z)y{PlP zw~87&R|R;c|_m2ao7|iW#Do{?%<<#hapl+&(6oQ1_F@pOx)x6DDW_z*@48fG?!K)a>w-8 zojc#2wE6{!Zvw}l5-vi)-zU|ki(n)Cemnf5`DS0Xe&x5JhZ^cwCoKA1{U$ znZg@c6I!OzTxOjXp%ng|SF+SNO-|Xh6c0-jrHSasXwk--QDL=B+kc8j-t+#4&MiVE zj&?~*?h7}AGl5fHId~TXiPhVuOkIPidbE5@dHdQ)OfUu?WAGi0%b4^MJNl6Lc|+q+ zIwJRd2%Wo+b`aE%cP|AYwLqLJH+DNo=WarWo99}**`xY2F(*YeL%S76swzAb{UU?g z{No6Z+#=rquiRV}x3XH{<`V1>QCXyTZciB-(&jVq-#w(^OT4`3b%(L@~9x3sgZ~7do`061&=s-Egikyb=Accm_zC&&ZWd|gg?IgihZOyUmc-_1 zGr+}D?q3%wKBXpWcYxCJ%;-NpOx{I)El(yJ;~R|pXj~o}k1t+%nNVMAmM*g%SWQ!v zu)2Wb?2KdzlRaY}Tq;F)T9?#XB`8OO{aig-RQpu#%iNE2N*Fw@(HR35NmlXf zc6p7(t`=(r7a}kgS+l8eNObOl-ykY63Zn;p(rrAc+J4e*(f}8p^CG4jdq3wxf}cJk z=jaHF<}a=xAf2HZY$jbsTKcri5naJ29LUsMuO5pLF$}+8>`^(_NWXic+Pw#7A3=VZ ze%qTqA|CRpWX1fcv89IU5_i|j#%)yuzE4WFQrS+ zi2-|t9AcvUgw>!;Ujm{4y;%A@s8gHl)Qmm)MY8ZhkiTQFx!{WlGl_iK8%iaY!aj53)|b<|87{11p!X|m=l^5+=UU+^9dD)n3=+KPK) z8QrXggST|B{dUOt&TeB)XO})aT_pb{$qbb4%?(+-g|MdVP0Wk05uEzHOA$g@ZU(JL zKKAPaN13!ad#hHyQ0+(#^p#y#w1tFlkp<2Gy~ibcnL0a-JZK-Au8oDc>JK#aSXK~C zorX6r=eyOnMJKah)|^uJA}y$E4%{E7lX%^DEirTp9j9-!rGAMmbRUpVfJdf1piApVajdR}?ORlMD z1lO!p=6}%sTB$-8YH$m^pVMIpX1y$|xC^c9n{V!lJMyaiR)m2+ekGK!s=wKEIVL}0 zexa3}W#C5K-MXcsmk?r6VllTE zT3O?iZlPx}N1A*$rZ<;n5~f@`1l>rp-<`?Z6>L>{gKRXrbsHFf1CfIS+zMyHx8;Nq z)q~o~7uoSRkev_IXh!VsLwuo8fx4r<2<}^rqRT+xc)fs;h1QIKm=Z%1QIp_vF1$Am zq{8K7)0$QT)E6y1Gnad|5?%h{YoBno1d8{_!Tps{`mesiQrqbje?}PcOn7f&_=tdj z+kP#Pq0a@mx4zt*)FhfBd8!yC43zxA1fnKS9@8o1dTPWyRuV~8Ol|zqU-gzy?0Dt1 zH6@PkO>aUHT&&Ex<}|d-b3s6^zwdjU7B=>4STTvL45aa>mtV|@*ND_3iO?&{1}x7C zl!-k%v6qQ=vNF<)>!H`xdsmlhm^1Zyf|Z7fYaJI$Yb&fC4Ajtp5V$V^0RijM^s#X< zpDM-Zk*!Pc?{!w@fdWZX8SYI8=Wv$B#o>C>mY1}I1m(SNKmgwseIVtosaXfdj>TLp zZD(o6u2GQhqo!BCfPOGX;181%Rj+eyk)U?vFuoT(2qadmoth zfh*r-xaak^@AVsiVLS_Dq4c3!P*!Yg25|`qYr~k>*w;F$-JfLf+;2yv(TD_MK+x5u z6I(iB&~T>Gjn`0R+y~kTSl^vNu<3n`Il)s+X9^HAeax(0gI3&18C9Z~-NP?(eW~|^ zRXt|uVkHH&6u`4qv!azSf~jpVu(7daDL7O3IaofP#0{d6a?!&>jRq3Lp)hd9i*hWks6@iuGSCxtq9K_VX4)=-a&4Z#>_ZR#W?ysUk<}}7GEf;p z#2Yr7M2ItE&Xa=4My2Zgk$mdaS^8~y6lFG8E}-@uv*lvpXslMJ)mrLm=`nUBj)Vk! zf6OZl<^G0xyJ@hd(g(iI*E+E>#Xtcm#F9s1RNzHVL zP*V51@6`-1(4czu>>1zD?MeN~`CLaf(bo44h(DOvS+ckW&!eCnN}~EB-+2=_&4$w9 zucO@tRa;JJ`uh8S86q&Kuw~>lB&7+v*#f`N76jc!01}7odJAeNg8k>SeTqsItOGRl z^{10mE@x*`SF6FS@2hPMkju`FmeQZ(f z;?wn_kA|oF6O6cY)mBTSne@~QT-VYP>(E?yZ0z>u!TX*V{QDziTqnLK!&_j^8;oVi z%I=vX=kb~?5?e{>VYw+~_*Kiu-R%t5h>M7utYB|ncn1W?1gUixr)vw}STE9a+g=%{ z9*_EyakyVv1F;iXfG?^C@uuhE(HCjY`&`JRo(gb+!9{^!M}D_n_Q0^}n%PS0_lALU zhWcTG(-u9hk4NHLIsvigP=>f)0;dy;+xb4l(8hOA zqKbe*N%@2PxrD_1#}dc)MKi@j02_k&kl1uCU2X-V6%c?+#rd6tHi#0D)SV4eB9PaeQxlCCH#cC-Wdi&3w#Z(f3wODRaFny|9tB`xBGzY0LkM&|Nbdy z`rq9C&p-UXwDtG)-!%3AFI&uDq|riQqtlWFdJ&Ltc@#Fi1&}{KG)TyPZq~aa&n<|l z-QSXX4XJcmewi+>s-X^K4Z{nlr-m;0%N^NOhc93ZGiY)hbzY{{WFbJ{y_MOC1lS<$d{7mGfo?fFhfZDx)u3{DHyoOm-H^e!zh67ONO)bFqF z^KUN~`KB5mcBk)TTkdsJOmt4HArNDa{(c>ySh9N;-YJ%IhHUtR)X|?>+PC|?#kEKf zc~S^H&DGUUSsgLs+1?J2Wv^aOtnIq`eW40BAYIH{Y={RThp-jPntIop zxd4b{Rnlp-!7m78yMl|}r3rHMXS)1X!~O5X`ad|_|1Y)Z?Qp)I0V)&`VMq9HR2K=p zvyT6#UeO!!&-L%zCI9#K-wybLz574-tk}QJ|2OUaSI_>zmpv@v+kZas|NI*NRTJd@ ze5U{E+5h~ye}3kF`x^h%v;X$<|MRov$%mUm>+9uCPe*KsWy#v0REFA#1d{{A90=$X z{T~dYe%%~CH_Yi^8^|2Ky9DgJ#?|~>B0VhIg%8Ss)GaE zr20FfKij`VCoBY5E!b+o>si#)G<4tU>fQ&#gso+$Qvhp=l9F-dHldQ{BMdl%0s@Mv zjTdsz8vrcKKt4V*FAv$KygY9)AfP9WX}jx3*FAnYj_tlq!z64#VBpnSH9NbjkSQ>A zWxmTCdu;|HKtOwMB+78qW@e11%P0V9)IX|%qx0Pb2Kb*b2`_rw=W1#Ma`N)8X+Nwx zJl7;%rO`bQZQ@bM9NX&HO858@O2o6g>;tEcMNXNS7Yp;b7-*{ny{HBTu0$t6W)%4t zhWFLg6@46r_gj?6;s$^8KAUCo)c`Iv=vlnZ>WV+NK;s3q8VC zR+~b5?J6fH+g%#vv4z`v;UsO|0a)( zaO)Yt>=aldYBX}1UQvO&vek_VS2zO^!4%RxdlNpDII?N~F&p>9f-M4e4ynC=b ztO0P~aFs!-nlk-EK^V*I`{)Dc-weFqwjBjP>*JLIj zWN`*~Tbuo9_JJgB)V-8 zkJj56X+9%?PgAchv!3A~7IJw!e5C;kQ(7dHa{#bjb`uq5~F=!dm*p)DRyB(MR%*FOg`6kYcsQ)1O7 z@DWxyL=4QwEZq0-BLp$k)QJz)>Bki6z{C12Qv01*JYbxUsimblDwHRPENf?_6tii?CjV+x>%qVnx2JWbmruF^il9r z)~*+=cg*U}&9m9R_jK;x80|H>b?h%z%eRs#%KW}xQxXwR|EV-Z4FzQ+BP||o`w{xL zRrzn(UHWiS%b{bzthGJru zG?Y&u54%jy`@%|Iqv1q9qcj&pkd|(b8%*Z@`ca(wF)Ac#e;{fm@hQx)WZh3l6r}Hg zuIx-Ln4Z#Xv_?x%p~lF_V8w}ucXh9{#dqmwD)GV(5mQRemg5PNW?uiXrp*t$Sri@s znqZ2|Y&#|3WcxTyKYvr1zS4xsBGz8^;gHEwxYg#HR2}eC%k{PtnIYyg4S07*Xd_2K zOjkvX+1~Rt3Pb~mf~t@2AAoD>F3o)Qmu!1g{B@$uk2D&TFZLIUIiV*)q*@(I zTF{3QfjU5I#Ko>=zxt_U270L%-VWQ4Yr7h-wf1f_3?aZ&KD`@7Asi_#^!Q!_pj8 z6N+^d`(_?|!J}VJ*T6}9#e#C*LL#6m@!@N-*wkT(Rm&A3$!x8(tE<2>Mn-mkmt0@p zSOFO3o>+aav|IBmJu%}7ZObnMA!yA;KMe=%XGms7RE>6dEvH`@9d@V#&VVnx!Vah? z*Dk#C&fi#O?2eB=X!S`y!g3vkuh&jPMP`2VDP(l&iWHNl`G%$C^46{@D)Yw>iJ-ku zqMDjI^7dr2U`fNZ>7|k-;(V6LTjzC;+6-~rP|KE`9KYHH*F6?m<3cLRpquI3r^;gb~2V_T)PAx|3 z)u0vEyf6c)=Qf4V)p~SKZ*RLL1HPuigtGBsRsPU)Ji(PZx%EW;TWQ`~2VOMK>-^j* z`d8}e1#VsM^s%!;?RCQ*AQ$1fbzT=7l&WO0$ zz}b=KhIo3gq!WL}@4Aow1&t&qPMh_4*S6inMNuW2=ckHc3jM=^1nWQ)Y~X=LXa*)b%Pf0(Ym7JS9DOnZLzo()SZggBbU^|ZP%C5&6j z=&+wZsjSNK)AMWf=cVBe#KNrPQ^Cg~Fs>~qh}?lz8^m8l`>$NB5_d||@t%@lGGo}G(hL0jO)RD5Hb)V;2Ik!8|}>#9$M^RZWQIVVDWnDh`LxsqSd!;8g z+Tl);$I80s3ZJW78P|TxF7t|!$c_p1w59t{XqX`jVe&y_$C}hSL#R#C zZqe{52ft1zE6zY6hpKV=MH766Ha>QR0~-BN8yZ$?h`Qdi>O#lDGXGYtb7fX`-f5sa z0)5|CxTk$lr588*Eb=07MHzv3;rH}^>)S((nQhe~)o8aN>jOEN-UX|}*qY@vLoCbc zT#;|2{(UOzH9sdMtnFenGR8Asx|*l_P9CZ8Q+w{YbKg+)x!B(*Q~X;MJqE>VUs6s~ zZ2KG>OsrB9;%1nZ@DYbKJ`w24ziR>$bN2%%cL7X*J> zc~ki#RV5Y+VT*TnK3987*zcJ4sda4|HgnakflKcS1ov!biqo7AYs#?P?8!*s=@`rFoQJz4yOZem7< zR;-UV<#t@6)v4P)DcU7hSx}9FDNp3T&zT&d@F*v$U~2-v*}9J1ylcD@+*GDTWagK@ z4Y}!jL6fkyhF99I;&<~1RmJ6Q`AIf{z%k2_U+|YJ!Q=?_p2bK&pGE!sa!w3#3PgC2N+i3uylKPZBc!3wWfb?T_ayhGyPx zDHF7CZ~sK#a7r4p_Wt_}RT6X8vlspYlEqJ?<7kfLxl8gmT4Cf4akC9k|Gqx0QVs;8 zfG#a=<@Da0cixjo2TtX(HAY4CKb_n;beDjy`~{h%hz?`1JlgC}|J*9c$={IweJ6>+ zXOzAjgn@L1e1&rxXMQkC@ROI}xZ$^K|9PMH#&&AxaVP>W6Oap1>Rs5Di>o_-AJp2x zv58TQmFb)Q?Z|h^xY)!a#>eAmMzv38CJufP=*G6bEtp6k{M(dd8H15Jwx)Wioy2SF zm!-oj%dR=e2#~-3y@A$7k>3@)YcaGiy&S9j!>K{ILCi2LTO0H5D@$={yo^PYf2TQb zYBR3e=4KYi=mTbr-LvYsm%@J^DtL)){i=EBrw=D0oVHg#vpf2G1B~oBOUZwKPZstK z3EPAo99H{h2Ah$gR86foCb%gMBftp5`JZPBC@J}xMwev?h7K=W^h*1Ay}36f2+{u2 zwGz#;y|}2}XasSTbyYLVr#(&CGMX(lUFdDz1Wz%cSbF8dI7o2PunvDm^l^4yigw#i zskve=?E%`AAa?Ovpq@W!9*ZMs`|Um6k^bV+hAbY(E`2EyofRC zGN+Oc%3)StlYL;CwID@p!kTVB|J!jU+4PqmYP$>jC;%%_2I{+ki1EG9Vn_x&$DGpN zm(EV%Z=G515pmD>`GMca6D4LKVBGRQQ+q!DSrGE!g7I-@3V$(^%K|g+37+m}0xZm? zq;kGxF;WB|@ZF35w})}XX-{%J(=X7zG!b1se#^pK^Y>Gmlqln2w^N)UhFfv*H!cC1 zEfyVEmBcss&;Iko;RYIZmEESVlwY*n=7D7Up=JD@kH}kE?2us4R~&A*uW-f6@(BTN zvYj9U`83s*MFNxutWU%qCqs`e)}TT2KD>7{$&?9r-@3Cuh9~$~^u8pKjmkp4SBvDl z;Y||yJW!8{y1#pN319XdS60#|t64sZ8{z)@13~bZxfL{jG>LWU{IIb4m-^H{RS@UR z;FK%2@mOL_yX+1W{24qWSUEtKsh8VWSizx`Hn4b^`Zo8SW?!oj40)os3OZXM+qwb| z6U=QYl0=`oqQXQh>OjA`oaB!;%Aeo8CD9uy3A@raAE2vPQq@U2kia5Q zzLl37=N;xQyRB;Rq!A_}ck3OtmmP0Va7DI$1FkV;hK}mDTSGYraWOT$g&$1ebg{aXQ##|eoP?yz7lX{STzoKe$J5ZqW}!0vjxxDna?Eq`kJDHd zrsp!wgH$%_O9ciK4j#h`u}H&Us@}brZERmI9X8JIC-1m@4x6Bw`Z46Jd%g%yr1u)0 zMe4>ZSH5uypZJ`Z;;e~8)ash)`o&x}H?&+-Yv~1{V|Wand?A$KKyB;ZzExqDdrbFi zjNW~H{Da8?lgWkp&ZVb!>5b4O3v^+yW+=;u{r|V007A-+rUU+Y2H1*76O|vwZ$W;z5w=AqqaV^AW8Tn4ifLSO_U=?2* zgEHPG<>T#OQyk_|gd!=&B^^P@nZuiIOLzo6-mtBkplAe(&gx$<_dlfhcwl)GODqBJ z@WYkbljWj3aV?`9o0Be(Z_DP*q8Iz_on{53O*t13v1MgZ>mK?Pk6DRQ$C8P1YWf_U zl29plhP`_?%Lb8277MbFM>|QXjTFE{Gq&eP&V$XHsek1C@p#O{8%@u27@d((NzUtz zSU0L>sCQ@lTxzF9Res8$gGY6!ID1fCZqHEO>#EA$JpGP*SUBx>^f|iL3Jjzoc?!sQ z|FY<)_0-FD)BZqTa{D_eeD$Nr!b_7ordF#N@m+zcW3R1WJLr|!YNF(IuSFpv1}($AvqFK1hb+YVbOHZueEe-{NFD6g9hT~XY>@*)GITY_@D7x9P+kqu~wuDrx~ zaN$bC5l`;a3;1XpNXgL~c`GJ}I3b@%oQfh8NnY=F7Zb8h`&k`n(=p#xd&M8$_(UHI z-|l!_=s<3Yj@<5aYq7&4E#0shyR~@sxluhCnD6|yKK5vhT^c!u+={F!O}p+rR=7a-oy(aJe ziHHXAlXi4*cW|&yuChq1I$s+5WF+$~9sguVpm}=Zh30PwQjL?mQAIEM=%|xEhhBsf zS}M;ISd_?A4?EGD*Zw7MEEdNdgN3g;#cwPqY@~nGWMgE^pW&FaQ6JtmWHi?AV@@p2 zB|mR-@hyNaEMs&V__oO4uq%^JG}@hVKqgKU!+Y<(+`6AS&C==SNz|M^hIHSxg<@`@ zMt!%zIp)J$Kxba|+iEOqV{H5>pLLrng^aa*X{j5nO*b6OP~dPG<~opAl#^=+ij9eh zNyB`lQJBf}Hok(Rxq)Zu0LbsyT$bHC)Qb>htX~4U1cxbxKi7_F^kZz!R?12?jwL^T zJ~P~U%L*(kmR;Htt?{imipYM%SeRqyqo-3}*8|K5;)92ce{OBwzl5sZ)CHKo4MSl= zeq}T0;g`G{)H7npUpq4eK5CvB52>`8Og4s`_)Bbu5jS)D@m86SEjwhX3fVYV(AfDxp94%O5^YgOC@&8 zc)*~#Hj4r2?7XjWuq1NUHq{%_sIl{2oAw;C>kUEDVRazI-QY*ts-yMDQF`5xx+lF8 znMXHN9VyT9!Kv-z<>$RNPDA$q_R(~D)bBPd9XQn$W~;6NCqzxOMJJ7KX=+Jejt{MD zieNT-Ti(`L3ay0`E{h56>l`^R>ix`9)1DiFs9$24+6fcvo=$9-)jdYGM$SvQu-nP; zd{eqIMs9@q6KOMvJ9Hb>f}MvWP?*)=IdMl5t|lk{*6b2K?}4qznh0aSz`+Hj-(8n> z6WurAYdt|JuW6?Q%nys#dnXD_vh%dOVzZKy_dQ2RHP&~ z$ak;DZB;etCJDTLh9_)o^NI|(bv@TOWpuA%bKaaMa;>L+x|J?MdoZ`{U^WvWHzA8o4)NrzLj-DMhzacffL@ zc-5M;hQc!P#6ZY9BESrCgx>ay&wme>1u4d@NMC_y8qkqmJ7sw!qubLb|8CoZFvHx` zt@)xUj^7*lB`uiMKlT|Do96Z&Pph70>w65NUmo}Yl;+M;`Mo1JxT;h@&7u-SFBLe; zwdB&v9E5zIj@e)KoAY^56@KSaG#$Q%9v*i1#1USRVpy7;yL|^qJQOmkpJ1iaPC}NV zq{1bJliYnqK(w|p+ec5ezIUJ=OjchCPjWuz1Yg#*RKr4{K@!m;^bvIyR(nl#8WZ2} z=GffVIqt%K$ax!teu7Fhfa7l)A$VfnqvklX6 z$!gVC-C7NIEv>d`OHwh2f5o%u09!^e@!dN&;iAiA$o(|F8)d1_{N8z+rTcI?`%r3O zV!U^Ln+wDxMzNwaHtzLLV!;*FL#V^KkpWGLmt&rsqp%N;K{>6-;@Q|e zbIqE=Lb=(v=rG>>@Ln5_x%@F4S%)f$HT&duOyy0h5(Mub{xgkOZiF`kW|@;U*y%7$ z*mobGMSK+IYYvlw=iKov*f)q_4}ZhAP-Bh4|nNzvA*Z_QSch~#>DxqFvt?#l8K6Gp%)})vWiW zW4MDMejM6GdgpAVqk9b;!~4vKj}7b_&fo({p$D6&b{DKwM*=Sa_AgIpIEmZrnAF} zYdPoLqceZr0rq!9S9~4AtzM*U1k3ox$7{T{>_(y@zYj_(MfMuUnso4cUb@H4&D3-z zCWO1>j(@14n4C|C_`tYC{$I^~^;^`>7w^I%Aq^_su^=ejOC#N=lyr-9cOyu5gS1F@ zhk&G{$RZsJOG)Q0u$K>fpXWZ${R{5-X=mOuXU>^;&zYU~Ij=Q*98}At3uB3Z0Vl_D zUW8n7C*b3g3cD3u@>|cH*w46)0k>ktTFD5M56IolKt0+-$&q*w6sXnra?+zbZ3Bxh zW}aNkAEl89iaXz5Nw}M{V_!w9#&k)1B)X{w@}j1eB|i?e}2-4+mlEP$EMY~Xf!etVU9Ayu}=xg&5W zkWS@IvYO?6_KWxyt(VXTOEPl@V9~Qc!dS66 zR~$NA&GG%sB*vuW2+0QS-8%W~Y_}r0?(Pb6tCty2%94LXevYh1_gSV>@hu4)n#&Wi z0^1*6P9KM?O0f zx7-!Lhd7L-wr6AMAn(dgMlWyA?0y;S^Ua~Q*NIt2xrtt|;wg^bbv4{@%zw+G5(tD-Vd}n zJ1jC#{{EwCA-;s+eyFGf1*W%oGXi`nf^OgemU{V`C=Xc5lGekAqSdhJOiED{;P<>` z5Oy}m(HeJ_BBqaSaz@B9P~PQiQY~1*Kkw}0OY(OF?>k^MsBn(6E`khbmkpM0VxEk@ z43vQ5%WvoyXQE6L!DKGjo2t=vk?HPsD|M!QD%|GCQ{29(u8kX<;3wS$R9h)rC+p*A z-0DGh=w@+9TC>7xjn7ml-&#_+rCGSohBDSQJiWw@yTH;?anxjrH|;A zEaM|DHIeC6LTjJ$ z2g3pPn$JQ1)o&10jr3e}mx}?aC>rhYX1meHh)=pc0#|QDvgITI3lqo;NG}vdrpYtg z?YHa_qQiq0HyY;@3k$qGNN_Oo^SCJA-C=@<<)OXV^?tpr{{xUg^xa+ z4elkpw^>a<^@KpVc2x}|*%UKbW%KeOU|^9(LF7I8RlMX%K(Omg`ahrq>g4h%ciAWb zhThgqzeEI%iv+6$eMx78@NpAcPt3H4ImQNCG9_wFQkilY(We2OA+&paxLH|&&(JP3 zaziV$;A}vFaiDKPID3J!}JLj2mFzOZtt=TPIp=dcO$H~w826*@=UDweT1->Is1qkp09n|vR%5-$Sg z4{b%^l;}X*|0}#1kev71;P^SJ|J-lMCgNp*np$UgIPP4?u?DTbdFpSB3n1;~Np~A1 zq-|$9@VG1LYn4vY{v}}VoTvDC!1-N`e{38Kk8t*Gz)NZl-N@t?*m(SWAaccab46Dq z7aNtU9QlL%xGPYtp>^uEyOm?FcVkWOMr`p~YK6|pv6S}^bYXVT_QO96_XPrf# z1?81kU2|zyU?NSpg9Ony1*fDQT%^i@1&tKr18Va%4vPpJYdW-4WR%#r7wCh9-oU3m zO)9Z$4`c#xb4Kj}7Ogo-;~K~5nFH130FEP`085s`X=9X{18*z|(8mf`fe}ES_E}T( z1j+3ef3n=fKT4L?Lx+dnWVeI%*%*%f%M!(&@}NUPer6pYbf0%9qtg7(Dg6-&DI=*Q zI!9w)ko{cTS2VMdiNy?*w*>}Uamu!e=70gLIlvgpUVpcQ>8gXeK$=tL*@vAb#I2BV zX4^?B?8~(L?Vt;82;0ZZ4GJ{*18=Uz{-rcvR&iLj<%gcLz@=!XEf2e9^*|qEi`gDP zPm_f`$vN3SCt|chmE9ray1`<;=^Pe2IzRBG7l4E85F#>4WAx;V=$lClN`bD&FA^Bt zfSjx_Q`!~Y)%U#aCC8e4RQTPFR`Lrv9m&B~a!JKoV{_6cl91Bomh-oi-q}b}$)i!cB z$TuMRCSqFLSN14*kKpR7%zIJNQGf3VHtVd`wRzY}p%AK85wvY;4+3pBq+Nzl2dd<}IQHlRb}2S9uWa)-sf z{tC*7oM?)x@%T+Macx+PAK+ZkyryGZw3Qgk6tg5GBtSlw(l zs>e!=UV*LEjaAXAvx0VmIaG_Rlg;r%cBie?t>bZ_w)-}3L(ojF41P2n6S(_&|NdYz zf{iIP8F$+8p%%E1YB$vSXoD$~u@eX=v1v^xf2>rhNK{rSe%xXhjb9Tyn@fhFTn&jm ziKP?6kV0wu)~f0bTE*AkppHOuTqA|>;0*;jql8>#Yx@CE0YGvMpN!1IhQdYN%^sQ_ zCR*wtrCD)Kl9uPi?l>>hC<#!}P^yEZB`D_UM5w=_s!O}UNeQ~<{fgA0pU^&8{LZ!y zoGh}Nx2qW{q2W!jy~-TH^$aq_XqFd&cy=UD1Neau^`EStG?6I95I11&spugJRD$=b zZgdPlvGi^{5u@q&2Hp4`%C7~#h+1$e9)AJwT!=$a=qDxpJfK$r{t&o|ae@f_XntYI z>M?B9LKE`w?q=(tnSg*`Ms#>?d*l_D0M4o<`y^ zWJE%c{7fE%i*<-gbbafl;f$G>?ZgckAiDS>ouXrDhxhE@mmOL-fYZn;mtl2G)Vp_; zh|}KSAC_rns>Uy@g16n1Z{d}=vvM2XS32f5TfPp?GMx?zEBZGY&i`50bs-B+iD@mR zJ};x$-r`wd9Q?w!oLLa?b9MHU$O&+w};J z%n5Gu*<7<#=S2JE1-Z&pPeXofCtsd7rn)hDLD2We>he%j5f{2V#XtcllfyEWTVD?+ zlFqwA$u&53c>`rOKM3bU5HD`7cG|C+TwhqorgW*aPBMn>Ej5;zMW@L#a~$KEdW!pC za8q2ALv5KH^M58EsTb7=r)_h*%yqR9Qp85mj=p_>n9b+MYO=Ae-V z1=nB|09qrHrF}ld#hvZGj52CH|Au4)w#lrDPaIr}tOmDPk0xr|JQSq<7jD*$4 zC_!9R8ce(j{ort+Byc04+-7dqGuP%R2S}7$sNhXUn?Y3&ctfFbUxV=Ywv(nP?T)^Y zaqC$XW=3h=kY_*Dx^h5Ueeu&%0>#q zJmD;C1pO@Z{Bfr>xeZ>_v?!h0qeZE57Mye*$HQS6YbyI)t^KrSuWhodM26ZTx{Y=~ zx9(+<|wXF*;H_SGGO6Stybxomi}U)twq&1>RH5H zImJuSph-!&MJrFqp3>M0+FsikKZPZiULN=X%VGbO+qM9ikfN76J=e%|P>Wdhhaqa# zPjXl%w@^QfYo3EK;0h(?#Fh1DK3;QT+?U}KSLlL}eCL}gXi4_2$XW!w0e)-f{@_d0 z#VIC;-f|aq?eD&M>r!BjsiPz9P^A&<0@B!wJIb)|KT7dV9z~f+6!#^P9{Fy|A?Jff|pj4YLbo7i0&nGn9p!N2LTbv+Us#)nP{)& zx#c}(`rzb)aQ$=qK?R?Ps485cXFz-l>NWYbe|LeHtpDD8CI@W^Lu z6TfB5f&nGXPorNXmP!qUNCsmZ52-^usiO22&fk5*8hBcJ9p<&_#Mb>o6-iJCUfxMP z?!cjx_q;}5zBV(_3$=Fe~aQQc*9EU&a*l7!@01;#j z(9QFjv)_>&U~mZ%hXzQUbRX~W)lzMYX&GgKK*E>@PH>}neOEL|3h&sNi;9s&HWTfh zbNNIzFy6_E1D!TO<3K8`f#A*BKb5Mpmpv>pxf;}S8HI<1>x60yQBo~x(EbWIak~-e zldZ^|{hgTj&CVEK*f3Q%HY7!bdX*g%;;0QT{3q`-kw8<&k7H6V>p(3Kljbgq2xaxT z!LHCfND{h*CO8O0xtYFS_?AL=YiV7G|CclIJnZ#kE2mUh^Yj?)FS)Q*7Ryc@xcNs2 z0Rs)gz2mLaGgfWCe7UXmi(^N82RAeqQvb>f6ZWU19%$gs$Q*Qc!zT(=RCs$7+vVQd z&u=*oW+@MYFG%sX|Lmo=QAy^qjn2_tg^}0Q%l&nCh!|6A>XMt~Hc4)9;m0%^XTfB! z=igW5?9$Or=`#kQh>&dq^KZcrXX{Y(W=jItO z&vDt>SH}V1Y@fKN@BMFDjk;dtX(3Ag9Hc8|UG{YwW~Ty_7hPTS*hy)W?u(3~l9SI5 z(yVQ4pQYn)qpUe@mk3qyJ71#2{i35M2tZV4P50$7KLbub&(lb1&TWO$(^)3}CbTT_ z2Y)7f$+b_I98sAaUk4)m?!24kHH@7S%;<4=7UHG(R3qO%lJcLSM1`5Atu)XRBZ09Z z_=JEj;fk0}i=m@EXV}`^89$Vy;{y(+yi5YxK=qZmJ&<0FW{ZRv7!1!ggZp_qj*|sm z<@^?Jy0(qYk1J}2OF@%;c#^&k37)JuMej=)MlQq%nj1^>|L~kmJ7PC13V+pR+Z@id ziwT>~KdmCum%GHn>=(Um;h?*CN1}ML%RB+4M8(+7ox6qZU=l6kMYXR?WY;ego?L-k za<}E*3P)}yXTNJ<@r$2%Z;#?fLADj)D6^#%nj2N=#6X-|Vd4Fx6YIxodP z_hN7lvoQH25l+t&wn;B=PA~b>o1`f$|4lc^0lC$qg!4e>f1cR!;cYIJ@T zIVa?_*X(;P4E2N~}h<^(Qd8|}jVO&R* z$1!?mvS-6S&?8xog_zeVMI*i0JB8Q&`{P|2hC^mS+XC95=pvql$*;xuK0o)_^EjO+ zeCc^?<0VHKN>_@=l40H*K|k4m@BPlt;&Pp8tpFxsC22`NP#<@AZa`2Gg%9h$zv6cb zd&Lab9z{%O#F@=HlQ@8f$vO&%Z(cxVkXWjW!-<1lC%jJFT2=8xTCD?EPjmB18xT)3 zIHlz2IT%%Cp3;2`6*$gK{~1x8gA4+==7G9HYfkZs18dOC2M8B%dTBlcecN&}B(}sP zq^^;-G9S#(f|8C%8PRHwi}NROM%1SH&nQJO$s~?&>((tGew7y?a(oDL1Vp zJh7Y#DTg)H7UFJ{(pl`j~R68r{g| z0w?U&&@miuAZEdSLKxlvxfrw&h%8OmSiiOM^WC*2yoAS5mZ;4tn6YrxJ3}*RIb`6A z*LW93N<%dr?z^z(u$CkbE77gL%V{lH6=VW+2_~aPFoHK}*)Jt)#In?)IcLSX$)rgY zZ^pg5FFz8+^L*zlFb5vwvRN=>*-rRjNL%vjq$?4uH8z-N^nop*7fUk-dvNs4rMm@z zlYbS}(M3Opl++kCQ^o1FI=O1!3-aHYq%x7M_;yZyine5W`&`!>1UR$ZTY;zYm}cbR z42B4agSyRNQA6AUGWbzyBcxzV5o(MM@a8u z*6CX3y{2U)$bg*>r}XiU_0t?qYx~kCVR3lkbK`ow2LGTf+oNzc$Aa?^MuAG>eKJTNM+UW=ONTXJ~#HP zo!htOuU*yonG^hI2jFf-rj8PdZ|34(x{Hy$<#v_mXY&Y%j*VY=dp7JQH|$4n)V#+q z7P%w*3#+$McAHYPnc)f9Fq?LPwcIN?G?u?d{&H1{4Swr^yel3m@NY}*8nj~x=}cSA zE&sMiy~sf#T6ljMB|UZ9U%+`87C~~Df5$^H8;ROI+vFWjflg!XON0`unWu3+8qEIZ zh&MC@vEi}laj|Wbvh?lYrZ_RRZPIyWRUbVR)8O>z!t zFLktYZ~0Gia7csd^3Nk)#a~N7pbUXU0^+%6(?2pfIRQFxesTLl#_56=_h3cEPR{St zs68$(^j!|lqcFsXmf@3O2j``^a`T$Aj4LJHxclM4r*mCf*cs67BSu*@^q;NW<+Go) z{Syi2d2q^RpP`evyg|0%`bo8P-m&4t?_w`;w1EU9a0iI?+6*Xgq6RvArBhWO>_cAO zv)!c>$VI?`aLzPRQ}OewGB83$Pr~|Z0!{$j$=W9&)GHwIyzI!2 zhQ;F?zT(w~M7`nK44T0FlW2h>Us*f`v5<=O&B!aM7svCkoCtOtqE8ZYDs&12QynK{ zMDZn*erVT6x`Ze6;S2P--2k;85@ zV=pk0;=;v|gKEQVvxjmAxr-3uAD>l!oOqe_dK^p>pNa>io^Z3<_z_nl<2>!QVbKgM z;Oj^lM8L1VPe8j2Jh?ZX;k!6<`MdH_OoiS7Hj}3GyGFGP=3Z^cxF?=x0;LX;-93^L zq0(`L1snL=gvxJd@a)Z{uM<#%cRY;+g0IPJEU{;BDS%Qt_iqCW{Hb(sIIz zc#TBWRCUD}QhrecF_a}g-{t6p$X+I_ z=fZMg&12*B&;Hd;?2TTYZ>3mSVY2ZB)jSVae$C`kIcwt9b)vO}E^TN?GK{ppY&h*} zW0vi-qB>(ae9?ODZC=^M;?RPe$-q$SNC12OOIu`uT6P#68E!z^uE!a&@v!q4o<%Q7 zIBUhnIW@l4ZEkepv;ysXcN_H;7(8RD-htpqg(c(=NY84YD{qQ%(d%Gic;vBQO0z)3(}L-NpMzw z*6gY}35lNQQd8f^D?_YUe^1j)Ho^b4b*s;FM>75~`X@7glq>h$LTzS5zpK6Lpb45J zmVkef_#?zOIqVy83F;8Nd;uqmgjJSk$o}c&7=-i8T7Vm(gGI;9Qa#ksP|3DtGXrtz z7O3~#yFBqC?N66!<)M!XeLW58r!K%lk*gX|T458CBIPEyjb;_HdXopBEc9s(gLn+F zjFcwzT5}E2er7N!uiN976uqN@zo^S-rq(`8*P8F#tgibE);#86qh{s&CT~C5k=Q5Vn+_IXaxt{w63$R80k*D(pO=QUi&z~LqUB=E4 z{%J5P>YEFVsy!V*G@o?cI;$@+00K4Zwh`dJ4cD59|Ha5MRGqfKVChCyev0H#{SO&t zZsGfnJ(Sgg0MFaiy&uF$E4OhF?Qg$8_g;2QI%Rdsm#wDU;|WtN0-y{lj4~wvAn?@` zsMz~<6uF@maO>&LCl40`0D4}$WZG#1PdDpky*jDn9^x6yOQ$Mb&ZN1=%W+-WLmUU( z9VWRSU%ZO7yvNcowmo~7;+C6@g~Ymv=~DXUF=$e-eSkGwh5VsmMTrS34-J&yaCAOBk> zg<&?oyz;?~8~sFzq#|=U=Ld*00O0%XxdC#gj^7B{`xmTcLBbl~D%sRuRtj}UywOTb za*lp*E0kCP-7|b=G1qjx{3#WA(6*Rko^DVgRwJ&z*~;j_C`7mLh#%*drrKsL(2hTMKac6C= zmkdWK%^#j* zroP9zVhRe13im2|_~FHY?nk-w`%7P0w|5r5AEf?oLNc=MC=EBT z^1iwPn*N{vC?K#)?fc7WuL`?*;f$@|V?nje^!)!Tw_AXixF0vEd5g|H1a=xy$r&-y zg`+l~W)=Z2N_rfq!I2Jf=uXM-$KU35yyI*N^Nzp%^qHhSh}Hu;KK5i4nr~`#=AYR0 z&DBr(rTxAxspU~HfL~tn30&z!XTidacceKHOvP`IBbN85RdQlivT_zPq-dgB8P-}! zZvL!E#sK$3_o3=)IkG7k++bZNoB^Fq>_{)d)h|&^Q+x8zsG^rG1R0mbjLd+x`5}7w z)vNbMK@Ym#H~99Q;i>0+d*IaP8R7o~ OQ+T5)Qzc~_{C@!c-NkYM literal 0 HcmV?d00001 From e13c4e8280b4b313766b31a821964c7b36a6ccf4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Thu, 19 Mar 2026 15:40:34 +0100 Subject: [PATCH 003/111] Update rep.md Signed-off-by: Adam Dabrowski --- rep.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rep.md b/rep.md index 34733e7..8894829 100644 --- a/rep.md +++ b/rep.md @@ -89,7 +89,7 @@ OpenUSD allows flexible naming, but ROS 2 has strict lexical rules. Prim names i #### 1.3.1 Collisions & The Dual-Fidelity Pattern Collision geometries must explicitly specify `purpose="guide"` and `physics:approximation="none"`. To ensure assets function across both standard physics engines and advanced contact-rich solvers (e.g., Newton), assets should employ a "Dual-Fidelity Pattern" utilizing a `collision_fidelity` OpenUSD `VariantSet`: -1. **Baseline Approximation (Default Variant):** The default variant must contain "convexHull" or primitive shapes. When the authored mesh is already mathematically convex, assets should apply `CollisionComplianceAPI` with `isAuthoredConvex=true` to allow engines to skip hull recomputation. +1. **Baseline Approximation (Default Variant):** The default variant must contain "convexHull" or primitive shapes. 2. **Advanced Approximation (Optional Variant):** A secondary variant may contain high-fidelity concave trimeshes intended for Signed Distance Field (SDF) or Hydroelastic collision generation, provided the target simulator supports these paradigms. --- From d624420c406bbfb23f769ada95de1f59bc678e49 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Thu, 19 Mar 2026 15:46:13 +0100 Subject: [PATCH 004/111] Update rep.md Signed-off-by: Adam Dabrowski --- rep.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/rep.md b/rep.md index 8894829..ac85953 100644 --- a/rep.md +++ b/rep.md @@ -200,10 +200,10 @@ Repetitive geometry (bolts, LED arrays on a sensor) should be marked `instanceab Lighting assemblies must use standard `UsdLux` schemas. Emissive meshes (geometry acting as light sources) should be avoided for primary illumination due to poor scaling in real-time engines. ### 3.5 Variant Baking for Export -While USD natively handles structural variants (changing meshes or physics dynamically), web visualizers typically do not. Converters targeting formats like glTF 2.0 should "bake" the active structural and physical variant into static geometry during export. Material variants should be preserved and mapped to the `KHR_materials_variants` glTF extension. +While USD natively handles structural variants, many of the simulation tools in the ecosystem don't. Converters targeting formats like glTF 2.0 should "bake" the active structural and physical variant into static geometry during export. Material variants should be preserved and mapped to the `KHR_materials_variants` glTF extension. ### 3.6 Conversion and Round-Tripping -OpenUSD supports a superset of features compared to standard robotics formats (URDF, SDF) and web formats (glTF). Consequently, conversions between OpenUSD and these formats are generally **destructive (lossy)**. Perfect bi-directional round-tripping is not required by this REP. Importers and exporters should prioritize preserving kinematics, physics constraints, and ROS API schemas, while accepting the loss of USD-native composition features (like layers) during conversion. +OpenUSD supports a superset of features compared to standard robotics formats (URDF, SDF) and web formats (glTF). Consequently, conversions between OpenUSD and these formats are generally **destructive (lossy)**. Importers and exporters should prioritize preserving kinematics, physics constraints, and ROS API schemas, while accepting the loss of USD-native composition features (like layers) during conversion. --- From 294f3f9dd1c30bd8595b87c5c210ce9d232c4a7c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Thu, 19 Mar 2026 15:46:34 +0100 Subject: [PATCH 005/111] Update rep.md Signed-off-by: Adam Dabrowski --- rep.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/rep.md b/rep.md index ac85953..6521761 100644 --- a/rep.md +++ b/rep.md @@ -1,8 +1,8 @@ -# REP 2040 -- OpenUSD Conventions for Simulation Asset Interoperability +# REP XXXX -- OpenUSD Conventions for Simulation Asset Interoperability | Field | Value | | :--- | :--- | -| **REP** | 2040 | +| **REP** | XXXX | | **Title** | OpenUSD Conventions for Simulation Asset Interoperability | | **Author** | Adam Dabrowski, Mateusz Zak (Robotec.ai) | | **Status** | Draft | From 28bd1644305d26f3c4afff2857ef74d474336094 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Thu, 19 Mar 2026 16:15:15 +0100 Subject: [PATCH 006/111] Update rep.md Signed-off-by: Adam Dabrowski --- rep.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rep.md b/rep.md index 6521761..88d8c31 100644 --- a/rep.md +++ b/rep.md @@ -15,7 +15,7 @@ This REP defines a standard schema and strict profile of OpenUSD (Universal Scene Description) for the interchange of robotics simulation assets. The scope includes robots, sensors, static environments (e.g., warehouse racks), and dynamic props. This REP aims to ensure that a single asset functions consistently across: -1. **Simulation and physics engines** (Gazebo, Isaac Sim, MuJoCo, O3DE). +1. **Simulation and physics engines** (Gazebo, Isaac Sim, Genesis, MuJoCo, O3DE). 2. **Runtime integrations** (ROS 2 Interfaces). 3. **Converters and web visualization** (especially glTF 2.0 conversion). From e74b1846913c0b9fdf63e3d17e6cc55336487f16 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Thu, 19 Mar 2026 16:15:33 +0100 Subject: [PATCH 007/111] Update rep.md Signed-off-by: Adam Dabrowski --- rep.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rep.md b/rep.md index 88d8c31..482c535 100644 --- a/rep.md +++ b/rep.md @@ -15,7 +15,7 @@ This REP defines a standard schema and strict profile of OpenUSD (Universal Scene Description) for the interchange of robotics simulation assets. The scope includes robots, sensors, static environments (e.g., warehouse racks), and dynamic props. This REP aims to ensure that a single asset functions consistently across: -1. **Simulation and physics engines** (Gazebo, Isaac Sim, Genesis, MuJoCo, O3DE). +1. **Simulation and physics engines** (Gazebo, Isaac Sim, Newton, Genesis, MuJoCo, O3DE). 2. **Runtime integrations** (ROS 2 Interfaces). 3. **Converters and web visualization** (especially glTF 2.0 conversion). From 1b9b9acb40878f284da2d663e4b8d192cebdc939 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Thu, 19 Mar 2026 17:01:50 +0100 Subject: [PATCH 008/111] Update rep.md Signed-off-by: Adam Dabrowski --- rep.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rep.md b/rep.md index 482c535..e803066 100644 --- a/rep.md +++ b/rep.md @@ -19,7 +19,7 @@ This REP defines a standard schema and strict profile of OpenUSD (Universal Scen 2. **Runtime integrations** (ROS 2 Interfaces). 3. **Converters and web visualization** (especially glTF 2.0 conversion). -To achieve this, the specification is divided into three distinct logical areas: +To achieve this, the specification is concerned with three areas: * **Section 1** ratifies 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 2 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. From f2d0703c1a5147903789dc3854d34eb479856a36 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Mon, 23 Mar 2026 10:16:34 +0100 Subject: [PATCH 009/111] Update rep.md Signed-off-by: Adam Dabrowski --- rep.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rep.md b/rep.md index e803066..66ce673 100644 --- a/rep.md +++ b/rep.md @@ -208,7 +208,7 @@ OpenUSD supports a superset of features compared to standard robotics formats (U --- ## Tools & Reference Implementations -A REP 2040 compliance checker is to be developed and shared with the community. The tool will provide validation of all REP recommendations for OpenUSD assets and supply actionable feedback for the user for each divergence. +A REP XXXX compliance checker is to be developed and shared with the community. The tool will provide validation of all REP recommendations for OpenUSD assets and supply actionable feedback for the user for each divergence. ## References * **[NVIDIA-ETL-PIPELINE]** NVIDIA, Intrinsic, Disney Research. "Using OpenUSD for Modular and Scalable Robotic Simulation and Development". URL: `https://developer.nvidia.com/blog/using-openusd-for-modular-and-scalable-robotic-simulation-and-development/` From 3654a524fa45b13eed48a435e04b9dbb80bd1c77 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Mon, 23 Mar 2026 10:57:55 +0100 Subject: [PATCH 010/111] Add Motivation chapter Signed-off-by: Adam Dabrowski --- rep.md | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/rep.md b/rep.md index 66ce673..e16b7e8 100644 --- a/rep.md +++ b/rep.md @@ -24,6 +24,14 @@ To achieve this, the specification is concerned with three areas: * **Section 2** defines novel, declarative API schemas for ROS 2 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. +## Motivation + +The ROS ecosystem chiefly relies on URDF and SDF for describing robots and environments. These formats are almost entirely confined to the ROS and Gazebo ecosystems. OpenUSD has emerged as an industry standard supported by a multitude of tools and allows artists to collaborate with simulation engineers without problematic conversions between variety of 3D and XML formats. Ensuring OpenUSD works well with ROS integrations across robotics simulators will increase ecosystem interoperability and strengthen ROS position in physical AI workflows such as synthetic data and generative pipelines. OpenUSD is a powerful format with an extensible architecture allowing it to capture all the semantics of other popular formats. + +While OpenUSD adoption is growing quickly, only the core standard specification has been ratified so far, leaving most of what's interesting for robotics uncovered. OpenUSD lacks standardized semantic representations for ROS 2 interfaces and standard rules for mapping to ROS concepts such as frames and TF trees. Because OpenUSD is powerful, it allows practices that are bound to result in low interoperability, such as proprietary extensions, defining execution instead of intent, and overfitting to particular workflows. + +OpenUSD is championed by the Alliance for OpenUSD (AOUSD) and the ASWF USD Working Group. NVIDIA also plays a key role both as a founding member of AOUSD and in developing OpenUSD for robotics through Omniverse, Isaac Sim and Newton. This REP builds on top of great work done by all these entities, extending it by addressing what is not yet standardized but urgently needed for OpenUSD interoperability in the ROS simulation ecosystem, and standardizing against practices that result in a vendor lock-in. As such, this REP is designed to adapt upstream standards for the ROS community, while serving as a reference to influence future decisions by AOUSD and ASWF. + ## Specification The keywords "must", "must not", "required", "shall", "shall not", "should", "should not", "recommended", "may", and "optional" in this document are to be interpreted as described in RFC 2119. From d66cee47db955a5474c1e1fdd5e791f33b83f91f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Mon, 23 Mar 2026 11:36:18 +0100 Subject: [PATCH 011/111] Update rep.md Signed-off-by: Adam Dabrowski --- rep.md | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/rep.md b/rep.md index e16b7e8..eb31987 100644 --- a/rep.md +++ b/rep.md @@ -4,7 +4,7 @@ | :--- | :--- | | **REP** | XXXX | | **Title** | OpenUSD Conventions for Simulation Asset Interoperability | -| **Author** | Adam Dabrowski, Mateusz Zak (Robotec.ai) | +| **Authors** | Adam Dabrowski, Mateusz Zak (Robotec.ai) | | **Status** | Draft | | **Type** | Standards Track | | **Content-Type** | text/markdown | @@ -19,16 +19,16 @@ This REP defines a standard schema and strict profile of OpenUSD (Universal Scen 2. **Runtime integrations** (ROS 2 Interfaces). 3. **Converters and web visualization** (especially glTF 2.0 conversion). -To achieve this, the specification is concerned with three areas: -* **Section 1** ratifies existing upstream standards and recommendations (AOUSD, ASWF, NVIDIA) to establish a baseline for correct simulation assets. +To achieve this, the specification addresses three 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 2 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. ## Motivation -The ROS ecosystem chiefly relies on URDF and SDF for describing robots and environments. These formats are almost entirely confined to the ROS and Gazebo ecosystems. OpenUSD has emerged as an industry standard supported by a multitude of tools and allows artists to collaborate with simulation engineers without problematic conversions between variety of 3D and XML formats. Ensuring OpenUSD works well with ROS integrations across robotics simulators will increase ecosystem interoperability and strengthen ROS position in physical AI workflows such as synthetic data and generative pipelines. OpenUSD is a powerful format with an extensible architecture allowing it to capture all the semantics of other popular formats. +The ROS ecosystem chiefly relies on URDF and SDF for describing robots and environments. These formats are almost entirely confined to the ROS and Gazebo ecosystems. OpenUSD has emerged as an industry standard supported by a multitude of tools and allows artists to collaborate with simulation engineers without problematic conversions between a variety of 3D and XML formats. Ensuring OpenUSD works well with ROS integrations across robotics simulators will increase ecosystem interoperability and strengthen ROS's position in physical AI workflows such as synthetic data and generative pipelines. OpenUSD is a powerful format with an extensible architecture allowing it to capture all the semantics of other popular formats. -While OpenUSD adoption is growing quickly, only the core standard specification has been ratified so far, leaving most of what's interesting for robotics uncovered. OpenUSD lacks standardized semantic representations for ROS 2 interfaces and standard rules for mapping to ROS concepts such as frames and TF trees. Because OpenUSD is powerful, it allows practices that are bound to result in low interoperability, such as proprietary extensions, defining execution instead of intent, and overfitting to particular workflows. +While OpenUSD adoption is growing quickly, only the core standard specification has been ratified so far, leaving most of what's interesting for robotics uncovered. OpenUSD lacks standardized semantic representations for ROS 2 interfaces and standard rules for mapping to ROS concepts such as frames and TF trees. OpenUSD's flexibility also permits practices that degrade interoperability, such as proprietary extensions, defining execution instead of intent, and overfitting to particular workflows. OpenUSD is championed by the Alliance for OpenUSD (AOUSD) and the ASWF USD Working Group. NVIDIA also plays a key role both as a founding member of AOUSD and in developing OpenUSD for robotics through Omniverse, Isaac Sim and Newton. This REP builds on top of great work done by all these entities, extending it by addressing what is not yet standardized but urgently needed for OpenUSD interoperability in the ROS simulation ecosystem, and standardizing against practices that result in a vendor lock-in. As such, this REP is designed to adapt upstream standards for the ROS community, while serving as a reference to influence future decisions by AOUSD and ASWF. @@ -47,8 +47,8 @@ To ensure alignment with ROS standards (REP 103) and stability across solvers: * **Units:** All linear dimensions in the USD stage must be defined in meters, and all mass values in kilograms. * `metersPerUnit` and `kilogramsPerUnit` metadata must be set to `1.0` in the root layer. - * Simulators importing these assets must apply this scaling factor to all derived physical quantities (torque, stiffness, inertia) at runtime. -* **Up-Axis & Chirality:** The stage `upAxis` must be set to `"Z"` and follow the Right-Hand Rule. + * Fallback: while interoperable assets must adhere to 1.0, simulators and converters importing general OpenUSD assets must read these metadata tokens and apply the appropriate scaling factors to all derived spatial and physical quantities (e.g., coordinates, torque, stiffness, inertia) at load time +* **Up-Axis & Chirality:** The stage `upAxis` must be set to `"Z"`. Assets must follow the strict ROS Right-Handed coordinate convention: X-forward, Y-left, Z-up. * **Root Transforms:** Assets must not rely on root-node rotations (e.g., `xformOp:rotateX = -90`) to align geometry. Points and normals should be transform-applied (frozen) to Z-up at the source level. * **Asset Pivots:** For assets intended to be placed on the ground (e.g., warehouse racks), the root origin should be located at the bottom-center of the asset bounding box (Z=0) to facilitate predictable drag-and-drop scene composition in simulators. Mobile bases should adhere to REP 105 origin conventions. @@ -60,8 +60,8 @@ This REP adopts the ASWF Guidelines for Structuring USD Assets. * **Assemblies:** Aggregates (e.g., a `Warehouse` containing racks) must have `kind="assembly"` or `kind="group"`. * A `component` must not contain another `component`, allowing converters to easily identify the "atomic units" of the scene. -#### 1.2.2 Composition Arcs (LIVERPS Constraints) -To guarantee that simulation assets remain self-contained, portable, and predictable across different simulator parsers, asset authors must adhere to the following constraints regarding OpenUSD's LIVERPS composition arcs: +#### 1.2.2 Composition Arcs (LIVRPS Constraints) +To guarantee that simulation assets remain self-contained, portable, and predictable across different simulator parsers, asset authors must adhere to the following constraints regarding OpenUSD's LIVRPS composition arcs: * **[L] Local:** Primary authoring of overrides and properties on the asset is fully supported. * **[I] Inherits & [S] Specializes:** Asset authors should not rely on `Inherits` or `Specializes` arcs for core robot kinematics, physics APIs, or ROS schemas when distributing standalone assets. These arcs create hard dependencies on external class hierarchies; if a simulator's environment lacks the base class definitions, the asset will fail to parse correctly. * **[V] VariantSets:** Permitted and encouraged for asset reusability (see Section 1.2.3). From 754967e5ef98147d765cc57a06974be79c3bc92b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Mon, 23 Mar 2026 11:47:41 +0100 Subject: [PATCH 012/111] Update rep.md Corrections to 1.1. and 1.2 Signed-off-by: Adam Dabrowski --- rep.md | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/rep.md b/rep.md index eb31987..3ac8931 100644 --- a/rep.md +++ b/rep.md @@ -58,7 +58,7 @@ This REP adopts the ASWF Guidelines for Structuring USD Assets. #### 1.2.1 The Composition Model * **Components:** Atomic assets (e.g., a `LidarSensor`, a `Box`) must have `kind="component"` on their root prim. * **Assemblies:** Aggregates (e.g., a `Warehouse` containing racks) must have `kind="assembly"` or `kind="group"`. -* A `component` must not contain another `component`, allowing converters to easily identify the "atomic units" of the scene. +* A `component` must not contain another `component`: if finer organizational granularity is required, authors must use kind="subcomponent" allowing converters to easily identify the "atomic units" of the scene. #### 1.2.2 Composition Arcs (LIVRPS Constraints) To guarantee that simulation assets remain self-contained, portable, and predictable across different simulator parsers, asset authors must adhere to the following constraints regarding OpenUSD's LIVRPS composition arcs: @@ -76,12 +76,13 @@ OpenUSD `VariantSets` are the normative mechanism for asset reusability (e.g., e * **ROS Interface Resolution:** A change in a variant selection may add or remove Prims containing `Ros2*API` schemas (e.g., swapping a generic robot head for a sensor-equipped head). Simulators and tooling must only evaluate and spawn ROS interfaces that are active within the currently resolved variant state of the stage. #### 1.2.4 Asset Management & FileFormat Plugins -* **Path Resolution:** Internal references must use relative paths (`./geo/mesh.usdc`). External dependencies to other ROS packages must use the `package://` URI scheme. Absolute paths and proprietary schemes (e.g., `omniverse://`) are prohibited in distributed assets. +* **Path Resolution:** Internal references must use relative paths (`./geo/mesh.usdc`). For distributed, highly interoperable assets, all file dependencies should be self-contained and rely exclusively on relative paths. +* **ROS packages:** External dependencies to other ROS packages must use the package:// URI scheme, and should be contained in ROS-specific .usd files in the ETL pipeline. Asset authors must be aware that resolving these URIs requires the host simulator or tool to implement a custom OpenUSD ArResolver plugin. Absolute paths and proprietary schemes (e.g., omniverse://) are strictly prohibited in distributed assets. * **Native Composition vs. Custom Prefabs:** The use of custom or vendor-specific string attributes (e.g., `custom string my_sim:prefabPath = "robot.usd"`) to dynamically load, instantiate, or compose assets at runtime is strictly prohibited for interoperable assets. Asset composition must rely purely on native OpenUSD references or payloads. * **FileFormat Plugins:** OpenUSD supports FileFormat plugins (e.g., MuJoCo's `usdMjcf` plugin) to dynamically translate legacy formats into USD stages at runtime. While these plugins are recommended for import pathways, this REP governs the *resulting in-memory OpenUSD data*. Plugins interfacing with the ROS 2 ecosystem must generate stages that conform to the physical hierarchies and API schemas defined in this document. #### 1.2.5 ROS-Compatible Identifiers -OpenUSD allows flexible naming, but ROS 2 has strict lexical rules. Prim names intended to map to ROS TF Frames must be alphanumeric with underscores (`[a-zA-Z0-9_]`) and must not contain spaces (e.g., `Left_Arm`, not `Left Arm`). +OpenUSD natively enforces strict naming for Prims (they must start with a letter or underscore, followed by alphanumeric characters or underscores: [a-zA-Z_][a-zA-Z0-9_]*). This natively aligns with ROS conventions. Furthermore, Prim names intended to map directly to ROS TF Frames must not contain spaces or special characters that could violate downstream ROS 2 lexical rules. ### 1.3 Physics & Kinematics From ba13aede20ec2147bf7dc6c6df1e882cd0435d47 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Mon, 23 Mar 2026 12:06:49 +0100 Subject: [PATCH 013/111] Update rep.md Updated mass = 0 issue and introduced some detail Signed-off-by: Adam Dabrowski --- rep.md | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/rep.md b/rep.md index 3ac8931..3c549c9 100644 --- a/rep.md +++ b/rep.md @@ -86,15 +86,18 @@ OpenUSD natively enforces strict naming for Prims (they must start with a letter ### 1.3 Physics & Kinematics -* **Rigid Body Hierarchy:** Assets should utilize Logical Nesting to represent kinematic chains (e.g., `Forearm` is a child of `UpperArm`). This preserves the Scene Graph for TF tree generation and MuJoCo compatibility. +* **Rigid Body Hierarchy:** Assets should utilize Logical Nesting to represent kinematic chains (e.g., `Forearm` is a child of `UpperArm`). This preserves the Scene Graph for TF tree generation and ensures compatibility with parsers expecting URDF/SDF-like topologies (e.g., MuJoCo). * *Simulator Responsibility:* Simulators that require flat hierarchies are responsible for flattening the graph at import time. The asset itself must remain logically nested. * **Joint Placement:** While `UsdPhysicsJoint` prims rely on relational targeting (`body0` and `body1`) rather than hierarchy, asset authors should place the Joint prim as a sibling adjacent to the child link it connects, within the scope of the parent link. This ensures self-contained modularity. * **Articulation Roots:** A composed simulation stage must contain at most one `PhysicsArticulationRootAPI` per connected kinematic tree. * Assets (e.g., a modular gripper) should be self-contained with an articulation root for standalone use. - * When composed into a larger kinematic tree, the composing stage should use the `delete apiSchemas` operation to prune nested articulation roots. This prevents reduced-coordinate physics solvers from fracturing the robot. + * When composed into a larger kinematic tree, the composing stage should use the OpenUSD list-edit operation `delete apiSchemas = ["PhysicsArticulationRootAPI"]` to prune nested articulation roots. This prevents reduced-coordinate physics solvers from fracturing the robot. * **Loop Closures:** Articulations must form a spanning tree. Joints introducing loop-closing constraints (e.g., parallel linkages) must use the newly introduced `RoboticsLoopClosureAPI` marker schema. -* **Mass Properties:** Dynamic bodies must have a strictly positive mass (`mass > 0`). Anchors (e.g., the base of a robot arm bolted to the floor) must have a `PhysicsRigidBodyAPI` but may define `mass = 0` (which implies infinite mass/static in many solvers). - * *Note:* Non-physical dummy frames (e.g., `camera_optical_frame`) must not possess a `PhysicsRigidBodyAPI`. They should be tracked using the `Ros2FrameAPI` as defined in Section 2.7. +* **Mass Properties:** Dynamic bodies must define a strictly positive mass (mass > 0). Setting mass = 0 to imply infinite/static mass violates the UsdPhysics specification, which ignores 0.0 and falls back to a computed default mass. Instead, authors must use standard mechanisms for non-dynamic bodies: + * Static Environments: Fixed props (e.g., walls, racks) must possess a PhysicsCollisionAPI but omit the PhysicsRigidBodyAPI. OpenUSD implicitly treats these as having zero velocity and infinite mass. + * Robot Anchors: A fixed robot base must have a valid mass > 0 and be anchored via a UsdPhysicsFixedJoint with an empty physics:body0 relationship (which natively represents the world). + * *Kinematic Bodies:* Moving bodies that are animated but not dynamically driven by physics should set the physics:kinematicEnabled attribute to true. + * *Dummy Frames:* Non-physical dummy frames (e.g., `camera_optical_frame`) must not possess a `PhysicsRigidBodyAPI`. They should be tracked using the `Ros2FrameAPI` as defined in Section 2.7. #### 1.3.1 Collisions & The Dual-Fidelity Pattern Collision geometries must explicitly specify `purpose="guide"` and `physics:approximation="none"`. To ensure assets function across both standard physics engines and advanced contact-rich solvers (e.g., Newton), assets should employ a "Dual-Fidelity Pattern" utilizing a `collision_fidelity` OpenUSD `VariantSet`: From eb457b25de5fbd9f5d7e1c4bf827a1641ab358d9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Mon, 23 Mar 2026 12:16:30 +0100 Subject: [PATCH 014/111] Update rep.md Expanded on Inertia representation and mass Signed-off-by: Adam Dabrowski --- rep.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/rep.md b/rep.md index 3c549c9..cb7781c 100644 --- a/rep.md +++ b/rep.md @@ -93,11 +93,12 @@ OpenUSD natively enforces strict naming for Prims (they must start with a letter * Assets (e.g., a modular gripper) should be self-contained with an articulation root for standalone use. * When composed into a larger kinematic tree, the composing stage should use the OpenUSD list-edit operation `delete apiSchemas = ["PhysicsArticulationRootAPI"]` to prune nested articulation roots. This prevents reduced-coordinate physics solvers from fracturing the robot. * **Loop Closures:** Articulations must form a spanning tree. Joints introducing loop-closing constraints (e.g., parallel linkages) must use the newly introduced `RoboticsLoopClosureAPI` marker schema. -* **Mass Properties:** Dynamic bodies must define a strictly positive mass (mass > 0). Setting mass = 0 to imply infinite/static mass violates the UsdPhysics specification, which ignores 0.0 and falls back to a computed default mass. Instead, authors must use standard mechanisms for non-dynamic bodies: +* **Mass Properties:** Assets and simulators must follow `UsdPhysicsMassAPI` guidelines. Dynamic bodies must define a strictly positive mass (mass > 0). Setting mass = 0 to imply infinite/static mass violates the UsdPhysics specification, which ignores 0.0 and falls back to a computed default mass. Instead, authors must use standard mechanisms for non-dynamic bodies: * Static Environments: Fixed props (e.g., walls, racks) must possess a PhysicsCollisionAPI but omit the PhysicsRigidBodyAPI. OpenUSD implicitly treats these as having zero velocity and infinite mass. * Robot Anchors: A fixed robot base must have a valid mass > 0 and be anchored via a UsdPhysicsFixedJoint with an empty physics:body0 relationship (which natively represents the world). * *Kinematic Bodies:* Moving bodies that are animated but not dynamically driven by physics should set the physics:kinematicEnabled attribute to true. * *Dummy Frames:* Non-physical dummy frames (e.g., `camera_optical_frame`) must not possess a `PhysicsRigidBodyAPI`. They should be tracked using the `Ros2FrameAPI` as defined in Section 2.7. +* **Inertia Representation:** Unlike URDF and SDFormat's 6-value symmetric matrix, OpenUSD requires an eigendecomposed inertia tensor. Converters must mathematically decompose the source matrix into physics:diagonalInertia (eigenvalues) and physics:principalAxes (quaternion). This native decomposed form is the strict single source of truth; custom 6-value array attributes must not be authored or parsed. #### 1.3.1 Collisions & The Dual-Fidelity Pattern Collision geometries must explicitly specify `purpose="guide"` and `physics:approximation="none"`. To ensure assets function across both standard physics engines and advanced contact-rich solvers (e.g., Newton), assets should employ a "Dual-Fidelity Pattern" utilizing a `collision_fidelity` OpenUSD `VariantSet`: From b2967904e435d60cf55d2f63ebfccdb7c81a49f0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Mon, 23 Mar 2026 14:09:50 +0100 Subject: [PATCH 015/111] fix: weaken collision geometry specification from must to should MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- rep.md | 27 +++++++++++++++++---------- 1 file changed, 17 insertions(+), 10 deletions(-) diff --git a/rep.md b/rep.md index cb7781c..71f6416 100644 --- a/rep.md +++ b/rep.md @@ -97,11 +97,11 @@ OpenUSD natively enforces strict naming for Prims (they must start with a letter * Static Environments: Fixed props (e.g., walls, racks) must possess a PhysicsCollisionAPI but omit the PhysicsRigidBodyAPI. OpenUSD implicitly treats these as having zero velocity and infinite mass. * Robot Anchors: A fixed robot base must have a valid mass > 0 and be anchored via a UsdPhysicsFixedJoint with an empty physics:body0 relationship (which natively represents the world). * *Kinematic Bodies:* Moving bodies that are animated but not dynamically driven by physics should set the physics:kinematicEnabled attribute to true. - * *Dummy Frames:* Non-physical dummy frames (e.g., `camera_optical_frame`) must not possess a `PhysicsRigidBodyAPI`. They should be tracked using the `Ros2FrameAPI` as defined in Section 2.7. + * *Dummy Frames:* Non-physical dummy frames (e.g., `camera_optical_frame`) must not possess a `PhysicsRigidBodyAPI`. They should be tracked using the `Ros2FrameAPI` as defined in Section 2.8. * **Inertia Representation:** Unlike URDF and SDFormat's 6-value symmetric matrix, OpenUSD requires an eigendecomposed inertia tensor. Converters must mathematically decompose the source matrix into physics:diagonalInertia (eigenvalues) and physics:principalAxes (quaternion). This native decomposed form is the strict single source of truth; custom 6-value array attributes must not be authored or parsed. #### 1.3.1 Collisions & The Dual-Fidelity Pattern -Collision geometries must explicitly specify `purpose="guide"` and `physics:approximation="none"`. To ensure assets function across both standard physics engines and advanced contact-rich solvers (e.g., Newton), assets should employ a "Dual-Fidelity Pattern" utilizing a `collision_fidelity` OpenUSD `VariantSet`: +Collision geometries should explicitly specify `purpose="guide"` and `physics:approximation="none"`. To ensure assets function across both standard physics engines and advanced contact-rich solvers (e.g., Newton), assets should employ a "Dual-Fidelity Pattern" utilizing a `collision_fidelity` OpenUSD `VariantSet`: 1. **Baseline Approximation (Default Variant):** The default variant must contain "convexHull" or primitive shapes. 2. **Advanced Approximation (Optional Variant):** A secondary variant may contain high-fidelity concave trimeshes intended for Signed Distance Field (SDF) or Hydroelastic collision generation, provided the target simulator supports these paradigms. @@ -132,15 +132,22 @@ As illustrated in Figure 1, assets should be divided into functional layers comp ### 2.2 The ROS 2 Context (`Ros2ContextAPI`) The root prim of a ROS-interfaced simulation asset may define its context namespace. * `string ros2:context:namespace`: Prefixes all topics within this scope (e.g., `/robot_1`). The namespace is additive in the asset hierarchy and with a top-level namespace set during simulation deployment (e.g., via the `SpawnEntity` service). -* `int ros2:context:domain_id` (Optional): Overrides the default ROS Domain ID for interfaces descending from this context. * `string ros2:context:parent_frame` (Optional, Default: `"world"`): Defines the parent `frame_id` used when the simulator broadcasts the ground-truth transform of this context's root prim. It is only valid for the top-most context in the resolved USD Stage and ignored otherwise. -### 2.3 Interface Type Resolution & Naming +### 2.3 Interface Placement + +ROS 2 interface schemas (`Ros2TopicAPI`, `Ros2ServiceAPI`, `Ros2ActionAPI`) must be applied to prims according to these placement rules: + +* **Robot-wide interfaces** (e.g., `sensor_msgs/msg/JointState` publisher, `control_msgs/action/FollowJointTrajectory` server) must be placed on or under the prim bearing the `Ros2ContextAPI`. These represent aggregate interfaces that span the entire kinematic tree. +* **Sensor interfaces** (e.g., `sensor_msgs/msg/Image` publisher, `sensor_msgs/msg/CameraInfo` publisher) must be placed on the sensor prim — a child Xform of the link the sensor is mounted on. Multiple interfaces for the same sensor (e.g., `image_raw` and `camera_info`) must use separate child prims, one per interface. +* **Interface prims must reside outside payloads.** Prims bearing `Ros2*API` schemas are part of the lightweight kinematic/interface graph and must be traversable without loading geometry payloads. + +### 2.4 Interface Type Resolution & Naming For all schema types (Topics, Services, Actions) defined below: * **Type Resolution:** Tooling and compliant simulators must attempt to resolve the `ros2:*:type` string (e.g., `sensor_msgs/msg/Image`) dynamically against the sourced ROS 2 environment. If the interface type is not found, the simulator must safely disable that specific interface, allow the rest of the asset to function normally, and emit a distinct warning/error. * **Name Validation:** All `ros2:*:name` values must strictly adhere to ROS 2 topic naming rules (alphanumeric, underscores, and forward slashes only; cannot start with a number). -### 2.4 Topic Interface (`Ros2TopicAPI`) +### 2.5 Topic Interface (`Ros2TopicAPI`) Applies to Prims that exchange streaming ROS data. **Core Attributes (Required):** @@ -157,19 +164,19 @@ Maps directly to `rmw_qos_profile_t` policies. If an attribute is omitted, simul * `token ros2:topic:qos:history`: Values: `["system_default", "keep_last", "keep_all"]`. (Default: `"system_default"`). * `int ros2:topic:qos:depth`: Queue size. Evaluated only when history is `keep_last`. (Default: `10`). -### 2.5 Service Interface (`Ros2ServiceAPI`) +### 2.6 Service Interface (`Ros2ServiceAPI`) Applies to Prims handling synchronous requests (e.g., resetting an environment). * `token ros2:service:role`: Values: `["server", "client"]`. (Simulation assets are typically `server`). * `string ros2:service:name`: The service name. * `string ros2:service:type`: The service type (e.g., `std_srvs/srv/SetBool`). -### 2.6 Action Interface (`Ros2ActionAPI`) +### 2.7 Action Interface (`Ros2ActionAPI`) Applies to Prims handling asynchronous, long-running behaviors. * `token ros2:action:role`: Values: `["server", "client"]`. (Simulation assets are typically `server`). * `string ros2:action:name`: The action name. * `string ros2:action:type`: The action type (e.g., `control_msgs/action/FollowJointTrajectory`). -### 2.7 Frame Publishing and TF2 (`Ros2FrameAPI`) +### 2.8 Frame Publishing and TF2 (`Ros2FrameAPI`) Mapping a deeply nested OpenUSD scene graph directly to a ROS 2 TF tree can cause significant performance overhead. To prevent flooding the `/tf` topic with generic physical props (e.g., warehouse boxes), compliant simulators should not broadcast transforms for every `PhysicsRigidBodyAPI`. Instead, simulators should follow a hybrid implicit/explicit approach for broadcasting `tf2` transforms: @@ -177,14 +184,14 @@ Instead, simulators should follow a hybrid implicit/explicit approach for broadc * **Implicit TF Broadcasting (The Asset Tree):** Simulators should automatically infer and broadcast TF frames (using the ROS-validated Prim name) for Prims that represent a ROS interface structure: 1. **The ROS Root:** Any Prim possessing the `Ros2ContextAPI` (often the `base_link`). 2. **Kinematic Chains:** Any Prim possessing a `PhysicsRigidBodyAPI` that is connected (directly or recursively) via a `UsdPhysicsJoint` to a Prim already in the TF tree. This captures robot arms and wheeled bases automatically. - 3. **Interface Frames:** Any Prim possessing a `Ros2TopicAPI`, `Ros2ServiceAPI`, or `Ros2ActionAPI`. * *Routing Rule:* If the implicit frame is connected to its parent via a `PhysicsFixedJoint`, or has no joint but is rigidly parented in the USD hierarchy, the simulator must broadcast it to `/tf_static`. All movable joint connections must be broadcast to `/tf`. + * Prims bearing only `Ros2TopicAPI`, `Ros2ServiceAPI`, or `Ros2ActionAPI` do not generate TF frames. An interface prim's `frame_id` is determined by its nearest ancestor that is a TF frame (implicit or explicit). * **Explicit TF Broadcasting (`Ros2FrameAPI`):** To publish TFs for non-physical dummy frames (e.g., a kinematic `grasp_point`, a `camera_optical_frame`), asset authors must apply the `Ros2FrameAPI` schema to the target `UsdGeomXform` Prim. * `string ros2:frame:id` (Optional): Overrides the TF frame name. If omitted, the validated Prim name is used. * `bool ros2:frame:static` (Optional, Default: `true`): Defines the broadcast destination. If `true`, the simulator must broadcast the frame to `/tf_static` relative to its USD parent. If `false` (e.g., an Xform animated by USD TimeSamples), it must be broadcast to `/tf`. -### 2.8 Kinematic Loop Closures (`RoboticsLoopClosureAPI`) +### 2.9 Kinematic Loop Closures (`RoboticsLoopClosureAPI`) OpenUSD `UsdPhysics` currently lacks a vendor-neutral (e.g., not `PhysxSchema` or `MjcPhysics`) mechanism to identify joints that close a kinematic loop. Because many robotics simulators use reduced-coordinate (e.g., Featherstone) solvers that require strict spanning trees, parsers must know which joint to exclude from the primary tree. * **Schema Application:** Asset authors must apply the `RoboticsLoopClosureAPI` to any `UsdPhysicsJoint` that closes a kinematic loop. * **Parser Responsibility:** Parsers traversing the `body0`/`body1` relationships to build the kinematic tree must prune their traversal when encountering this schema, handling the joint as a standalone constraint rather than a parent-child hierarchical link. From 1aab0bd9ef74b4a01b7bd7da973c995c97d3e755 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Mon, 23 Mar 2026 15:03:26 +0100 Subject: [PATCH 016/111] Apply suggestion from @zakmat Signed-off-by: Adam Dabrowski --- rep.md | 1 + 1 file changed, 1 insertion(+) diff --git a/rep.md b/rep.md index 71f6416..b6f8028 100644 --- a/rep.md +++ b/rep.md @@ -132,6 +132,7 @@ As illustrated in Figure 1, assets should be divided into functional layers comp ### 2.2 The ROS 2 Context (`Ros2ContextAPI`) The root prim of a ROS-interfaced simulation asset may define its context namespace. * `string ros2:context:namespace`: Prefixes all topics within this scope (e.g., `/robot_1`). The namespace is additive in the asset hierarchy and with a top-level namespace set during simulation deployment (e.g., via the `SpawnEntity` service). +* `int ros2:context:domain_id` (Optional): Overrides the default ROS Domain ID for interfaces descending from this context. * `string ros2:context:parent_frame` (Optional, Default: `"world"`): Defines the parent `frame_id` used when the simulator broadcasts the ground-truth transform of this context's root prim. It is only valid for the top-most context in the resolved USD Stage and ignored otherwise. ### 2.3 Interface Placement From 2d60b4bc3972b713cf10e677150e1705d02f63d8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Mon, 23 Mar 2026 13:40:03 +0100 Subject: [PATCH 017/111] Update rep.md Developed sub-criteria with more rigor Signed-off-by: Adam Dabrowski --- rep.md | 31 ++++++++++++++++++++----------- 1 file changed, 20 insertions(+), 11 deletions(-) diff --git a/rep.md b/rep.md index b6f8028..18872bb 100644 --- a/rep.md +++ b/rep.md @@ -204,29 +204,38 @@ OpenUSD `UsdPhysics` currently lacks a vendor-neutral (e.g., not `PhysxSchema` o OpenUSD is a vast standard supporting complex features. To guarantee that assets can be distributed, viewed in desktop tools (e.g., `usdview`) or lightweight web tools (e.g., Foxglove, Webviz, Rerun), and successfully converted to glTF 2.0, assets must adhere to this constrained subset. ### 3.1 Material Portability -* Assets must use `UsdPreviewSurface` or OpenPBR [AOUSD-OPENPBR] as the normative surface definition. -* Proprietary shaders (MDL, OSL) must not be the primary binding, as they cannot be exported to web viewers or non-native raytracers. -* UDIM (splitting textures across multiple files) must not be used. +* **Normative Surface:** Assets must use UsdPreviewSurface as the normative surface definition to ensure a direct mapping to glTF 2.0's pbrMetallicRoughness workflow. Target converters may also support OpenPBR[AOUSD-OPENPBR]. +* **Material Terminals (Render Contexts)**: A UsdShadeMaterial acts as a container. Proprietary shaders (e.g., MDL, OSL) must not replace the universal surface output. Assets should bind a single Material universally. Inside that Material, the UsdPreviewSurface must be wired to the universal outputs:surface terminal (which glTF/web converters natively parse), while proprietary shaders may be included by wiring them to renderer-specific terminals (e.g., outputs:mdl:surface). +* **Texture Coordinates & UDIMs:** Multi-tile UV mapping (UDIMs) is unsupported by glTF 2.0 and many real-time engines, and must not be used. Unique UVs must be packed strictly into the [0, 1] space (Texture Atlasing). If multiple high-resolution textures are required for a single mesh, authors must partition the geometry using UsdGeomSubset (with `familyName="materialBind"`) and assign separate materials. UV coordinates outside [0, 1] are strictly reserved for seamless tiling textures using repeat wrap modes. ### 3.2 Texture Baking Procedural texture graphs (noise generation, math nodes, node graphs) are not interoperable and must be baked down into explicit data using either: -1. **UV-mapped image files** (standard textures). +1. **Image-Backed Textures:** Standard UV-mapped image files routed through standard UsdUVTexture shader nodes. 2. **Mesh primitive variables (Primvars)** such as baked vertex colors using standard USD interpolations. `"vertex"` interpolation is recommended, as `"uniform"` and `"faceVarying"` require converters to split the mesh vertices to comply with glTF’s vertex attribute requirements. ### 3.3 Instanceable Leaves (Zero-Copy) -Repetitive geometry (bolts, LED arrays on a sensor) should be marked `instanceable=true` and referenced from a shared payload. -* *Benefit:* This maps directly to glTF GPU instancing [GLTF-EXT-INSTANCING], which is crucial for preventing out-of-memory errors when rendering complex sensor racks in browser-based tools. +Repetitive geometry (bolts, LED arrays on a sensor) must utilize native OpenUSD instancing to minimize memory footprint. Authors must only instance leaf geometry (visuals and colliders), not logical Prims containing PhysicsRigidBodyAPI, Joints, or Ros2*API schemas, as OpenUSD instance proxies obscure child prims from relationship targeting. Authors must use one of two mechanisms to ensure correct glTF conversion: +* *Scenegraph Instancing (`instanceable=true`):* Used for identical structural components (e.g., bolts). Note: The OpenUSD specification requires the prim to compose its geometry via a composition arc (Reference or Payload) for this flag to be valid. Converters must map this to native glTF Node sharing (multiple nodes referencing a single mesh index). +* *Point Instancing (`UsdGeomPointInstancer`):* Used for massive arrays of atomic meshes (e.g., LED grids, warehouse clutter). It scatters a prototype using flat arrays of transforms. Converters must map this directly to the glTF EXT_mesh_gpu_instancing extension. ### 3.4 Lighting -Lighting assemblies must use standard `UsdLux` schemas. Emissive meshes (geometry acting as light sources) should be avoided for primary illumination due to poor scaling in real-time engines. +Lighting must be authored using core UsdLux schemas. To ensure deterministic illumination across standard rasterization-based simulators (e.g., Gazebo, MuJoCo, O3DE) and compatibility with web converters, authors must adhere to the following: +* *Punctual lights:* Assets should prioritize standard punctual lights: `UsdLuxDistantLight` (Directional), `UsdLuxSphereLight` (Point), and `UsdLuxSphereLight` modified by the `UsdLuxShapingAPI` (Spot). Converters must map these directly to the glTF `KHR_lights_punctual` extension. +* *Area lights:* Complex area lights (e.g., `UsdLuxRectLight`, `UsdLuxCylinderLight`) lack universal support outside of path-traced engines and should be avoided for interoperable assets. +* *Emissive materials and functional lights:* The `emissiveColor` attribute on a `UsdPreviewSurface` must be used for indicators such as robot status LEDs so the source itself appears bright. However, emissive geometry must not be used for primary scene illumination, as standard simulator rasterizers will not compute their light transport. If a robot component must actively illuminate its surroundings, authors must co-locate a standard `UsdLux` punctual light with the emissive geometry under the same parent `Xform`. The material provides the visible glow of the source, while the paired `UsdLux` prim provides the interoperable scene illumination. ### 3.5 Variant Baking for Export -While USD natively handles structural variants, many of the simulation tools in the ecosystem don't. Converters targeting formats like glTF 2.0 should "bake" the active structural and physical variant into static geometry during export. Material variants should be preserved and mapped to the `KHR_materials_variants` glTF extension. +While OpenUSD natively handles structural variants, many of the simulation tools and formats in the ecosystem don't, including URDF, SDF and glTF 2.0. Due to the burden of implementation, this REP proposes both a baseline and an advanced compliance: +* *Baseline compliance:* Converters must export only the active or default variant, destructively discarding all others. This resolved state must be baked by flattening USD composition arcs into a static, logically nested kinematic tree. Never flatten into world-space, as this permanently destroys local joint transforms and ROS TF trees. +* *Advanced compliance (material variants support):* Capable exporters may preserve material variations via the `KHR_materials_variants` extension. Because USD can arbitrarily override granular shader parameters, tools must evaluate each variant state, bake them into distinct glTF Material IDs in memory, and author the swap mapping. +* *Fallback: The glTF extension is invalid if a variant alters underlying mesh topology. If geometry changes, or if the exporter lacks discrete state-evaluation logic, tools must safely fall back to Baseline Compliance.. ### 3.6 Conversion and Round-Tripping -OpenUSD supports a superset of features compared to standard robotics formats (URDF, SDF) and web formats (glTF). Consequently, conversions between OpenUSD and these formats are generally **destructive (lossy)**. Importers and exporters should prioritize preserving kinematics, physics constraints, and ROS API schemas, while accepting the loss of USD-native composition features (like layers) during conversion. ---- +OpenUSD and robotics XML formats (URDF, SDF, MJCF) are fundamentally mismatched paradigms. Because OpenUSD lacks native schemas for domain-specific data (e.g., URDF , MJCF ), conversions are inherently lossy. Exporters must adhere to the following: +* *Payload Resolution:* The active simulation payload (kinematics, inertia, colliders) is the extraction priority. USD composition arcs and instance proxies must be fully baked into explicit geometry and transforms, never discarded. +* *API Translation:* Ros2*API schemas must map exclusively to modern extension blocks (e.g., SDF , MJCF ). Obsolete approaches such as injecting legacy 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. ## Tools & Reference Implementations A REP XXXX compliance checker is to be developed and shared with the community. The tool will provide validation of all REP recommendations for OpenUSD assets and supply actionable feedback for the user for each divergence. @@ -242,5 +251,5 @@ A REP XXXX compliance checker is to be developed and shared with the community. * **[GLTF-KHR-RIGID]** Khronos Group, "KHR_rigid_bodies Extension Specification" (Draft). ## Copyright -This document has been placed in the public domain. +This document will be placed in the public domain upon being submitted as PR to a REP proposal by original authors. This text will be changed to "This document is placed in the public domain". From ae52dc0ff753db2a4c25c279265b15c22a62f7bc Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Mon, 23 Mar 2026 12:34:21 +0100 Subject: [PATCH 018/111] feat: add texture file format constraints to Section 3 MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- rep.md | 18 ++++++++++++------ 1 file changed, 12 insertions(+), 6 deletions(-) diff --git a/rep.md b/rep.md index 18872bb..03e7e1c 100644 --- a/rep.md +++ b/rep.md @@ -208,29 +208,35 @@ OpenUSD is a vast standard supporting complex features. To guarantee that assets * **Material Terminals (Render Contexts)**: A UsdShadeMaterial acts as a container. Proprietary shaders (e.g., MDL, OSL) must not replace the universal surface output. Assets should bind a single Material universally. Inside that Material, the UsdPreviewSurface must be wired to the universal outputs:surface terminal (which glTF/web converters natively parse), while proprietary shaders may be included by wiring them to renderer-specific terminals (e.g., outputs:mdl:surface). * **Texture Coordinates & UDIMs:** Multi-tile UV mapping (UDIMs) is unsupported by glTF 2.0 and many real-time engines, and must not be used. Unique UVs must be packed strictly into the [0, 1] space (Texture Atlasing). If multiple high-resolution textures are required for a single mesh, authors must partition the geometry using UsdGeomSubset (with `familyName="materialBind"`) and assign separate materials. UV coordinates outside [0, 1] are strictly reserved for seamless tiling textures using repeat wrap modes. -### 3.2 Texture Baking +### 3.2 Texture File Formats +Texture assets must use formats portable across USD tooling and glTF export: +* **PNG** or **JPEG** — required as the baseline. These map directly to glTF 2.0 without transcoding. +* **KTX2 (Basis Universal)** — recommended for GPU-compressed textures when targeting real-time viewers, via the `KHR_texture_basisu` glTF extension. +* **EXR, TIFF, and other HDR/DCC formats** must not be used for albedo, normal, or ORM maps in distributed assets. These formats have no glTF pathway and are unsupported by most web viewers. + +### 3.3 Texture Baking Procedural texture graphs (noise generation, math nodes, node graphs) are not interoperable and must be baked down into explicit data using either: 1. **Image-Backed Textures:** Standard UV-mapped image files routed through standard UsdUVTexture shader nodes. 2. **Mesh primitive variables (Primvars)** such as baked vertex colors using standard USD interpolations. `"vertex"` interpolation is recommended, as `"uniform"` and `"faceVarying"` require converters to split the mesh vertices to comply with glTF’s vertex attribute requirements. -### 3.3 Instanceable Leaves (Zero-Copy) -Repetitive geometry (bolts, LED arrays on a sensor) must utilize native OpenUSD instancing to minimize memory footprint. Authors must only instance leaf geometry (visuals and colliders), not logical Prims containing PhysicsRigidBodyAPI, Joints, or Ros2*API schemas, as OpenUSD instance proxies obscure child prims from relationship targeting. Authors must use one of two mechanisms to ensure correct glTF conversion: +### 3.4 Instanceable Leaves (Zero-Copy) +Repetitive geometry (bolts, LED arrays on a sensor) must utilize native OpenUSD instancing to minimize memory footprint. Authors must only instance leaf geometry (visuals and colliders), not logical Prims containing PhysicsRigidBodyAPI, Joints, or Ros2*API schemas, as OpenUSD instance proxies obscure child prims from relationship targeting. Authors must use one of two mechanisms to ensure correct glTF conversion: * *Scenegraph Instancing (`instanceable=true`):* Used for identical structural components (e.g., bolts). Note: The OpenUSD specification requires the prim to compose its geometry via a composition arc (Reference or Payload) for this flag to be valid. Converters must map this to native glTF Node sharing (multiple nodes referencing a single mesh index). * *Point Instancing (`UsdGeomPointInstancer`):* Used for massive arrays of atomic meshes (e.g., LED grids, warehouse clutter). It scatters a prototype using flat arrays of transforms. Converters must map this directly to the glTF EXT_mesh_gpu_instancing extension. -### 3.4 Lighting +### 3.5 Lighting Lighting must be authored using core UsdLux schemas. To ensure deterministic illumination across standard rasterization-based simulators (e.g., Gazebo, MuJoCo, O3DE) and compatibility with web converters, authors must adhere to the following: * *Punctual lights:* Assets should prioritize standard punctual lights: `UsdLuxDistantLight` (Directional), `UsdLuxSphereLight` (Point), and `UsdLuxSphereLight` modified by the `UsdLuxShapingAPI` (Spot). Converters must map these directly to the glTF `KHR_lights_punctual` extension. * *Area lights:* Complex area lights (e.g., `UsdLuxRectLight`, `UsdLuxCylinderLight`) lack universal support outside of path-traced engines and should be avoided for interoperable assets. * *Emissive materials and functional lights:* The `emissiveColor` attribute on a `UsdPreviewSurface` must be used for indicators such as robot status LEDs so the source itself appears bright. However, emissive geometry must not be used for primary scene illumination, as standard simulator rasterizers will not compute their light transport. If a robot component must actively illuminate its surroundings, authors must co-locate a standard `UsdLux` punctual light with the emissive geometry under the same parent `Xform`. The material provides the visible glow of the source, while the paired `UsdLux` prim provides the interoperable scene illumination. -### 3.5 Variant Baking for Export +### 3.6 Variant Baking for Export While OpenUSD natively handles structural variants, many of the simulation tools and formats in the ecosystem don't, including URDF, SDF and glTF 2.0. Due to the burden of implementation, this REP proposes both a baseline and an advanced compliance: * *Baseline compliance:* Converters must export only the active or default variant, destructively discarding all others. This resolved state must be baked by flattening USD composition arcs into a static, logically nested kinematic tree. Never flatten into world-space, as this permanently destroys local joint transforms and ROS TF trees. * *Advanced compliance (material variants support):* Capable exporters may preserve material variations via the `KHR_materials_variants` extension. Because USD can arbitrarily override granular shader parameters, tools must evaluate each variant state, bake them into distinct glTF Material IDs in memory, and author the swap mapping. * *Fallback: The glTF extension is invalid if a variant alters underlying mesh topology. If geometry changes, or if the exporter lacks discrete state-evaluation logic, tools must safely fall back to Baseline Compliance.. -### 3.6 Conversion and Round-Tripping +### 3.7 Conversion and Round-Tripping OpenUSD and robotics XML formats (URDF, SDF, MJCF) are fundamentally mismatched paradigms. Because OpenUSD lacks native schemas for domain-specific data (e.g., URDF , MJCF ), conversions are inherently lossy. Exporters must adhere to the following: * *Payload Resolution:* The active simulation payload (kinematics, inertia, colliders) is the extraction priority. USD composition arcs and instance proxies must be fully baked into explicit geometry and transforms, never discarded. From 80ce42b9cc8adbd8bdf46d50aafad715f73d6ddf Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Mon, 23 Mar 2026 12:37:47 +0100 Subject: [PATCH 019/111] feat: add geometry constraints to Section 3 MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- rep.md | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/rep.md b/rep.md index 03e7e1c..57f39d0 100644 --- a/rep.md +++ b/rep.md @@ -219,24 +219,28 @@ Procedural texture graphs (noise generation, math nodes, node graphs) are not in 1. **Image-Backed Textures:** Standard UV-mapped image files routed through standard UsdUVTexture shader nodes. 2. **Mesh primitive variables (Primvars)** such as baked vertex colors using standard USD interpolations. `"vertex"` interpolation is recommended, as `"uniform"` and `"faceVarying"` require converters to split the mesh vertices to comply with glTF’s vertex attribute requirements. -### 3.4 Instanceable Leaves (Zero-Copy) +### 3.4 Geometry Constraints +* Collision meshes must be triangulated. Visual meshes may use quad topology, but converters targeting glTF 2.0 must triangulate at export time. +* Non-manifold geometry (open edges, self-intersections) should be repaired at authoring time. Physics engines and web viewers handle non-manifold meshes unpredictably. + +### 3.5 Instanceable Leaves (Zero-Copy) Repetitive geometry (bolts, LED arrays on a sensor) must utilize native OpenUSD instancing to minimize memory footprint. Authors must only instance leaf geometry (visuals and colliders), not logical Prims containing PhysicsRigidBodyAPI, Joints, or Ros2*API schemas, as OpenUSD instance proxies obscure child prims from relationship targeting. Authors must use one of two mechanisms to ensure correct glTF conversion: * *Scenegraph Instancing (`instanceable=true`):* Used for identical structural components (e.g., bolts). Note: The OpenUSD specification requires the prim to compose its geometry via a composition arc (Reference or Payload) for this flag to be valid. Converters must map this to native glTF Node sharing (multiple nodes referencing a single mesh index). * *Point Instancing (`UsdGeomPointInstancer`):* Used for massive arrays of atomic meshes (e.g., LED grids, warehouse clutter). It scatters a prototype using flat arrays of transforms. Converters must map this directly to the glTF EXT_mesh_gpu_instancing extension. -### 3.5 Lighting +### 3.6 Lighting Lighting must be authored using core UsdLux schemas. To ensure deterministic illumination across standard rasterization-based simulators (e.g., Gazebo, MuJoCo, O3DE) and compatibility with web converters, authors must adhere to the following: * *Punctual lights:* Assets should prioritize standard punctual lights: `UsdLuxDistantLight` (Directional), `UsdLuxSphereLight` (Point), and `UsdLuxSphereLight` modified by the `UsdLuxShapingAPI` (Spot). Converters must map these directly to the glTF `KHR_lights_punctual` extension. * *Area lights:* Complex area lights (e.g., `UsdLuxRectLight`, `UsdLuxCylinderLight`) lack universal support outside of path-traced engines and should be avoided for interoperable assets. * *Emissive materials and functional lights:* The `emissiveColor` attribute on a `UsdPreviewSurface` must be used for indicators such as robot status LEDs so the source itself appears bright. However, emissive geometry must not be used for primary scene illumination, as standard simulator rasterizers will not compute their light transport. If a robot component must actively illuminate its surroundings, authors must co-locate a standard `UsdLux` punctual light with the emissive geometry under the same parent `Xform`. The material provides the visible glow of the source, while the paired `UsdLux` prim provides the interoperable scene illumination. -### 3.6 Variant Baking for Export +### 3.7 Variant Baking for Export While OpenUSD natively handles structural variants, many of the simulation tools and formats in the ecosystem don't, including URDF, SDF and glTF 2.0. Due to the burden of implementation, this REP proposes both a baseline and an advanced compliance: * *Baseline compliance:* Converters must export only the active or default variant, destructively discarding all others. This resolved state must be baked by flattening USD composition arcs into a static, logically nested kinematic tree. Never flatten into world-space, as this permanently destroys local joint transforms and ROS TF trees. * *Advanced compliance (material variants support):* Capable exporters may preserve material variations via the `KHR_materials_variants` extension. Because USD can arbitrarily override granular shader parameters, tools must evaluate each variant state, bake them into distinct glTF Material IDs in memory, and author the swap mapping. * *Fallback: The glTF extension is invalid if a variant alters underlying mesh topology. If geometry changes, or if the exporter lacks discrete state-evaluation logic, tools must safely fall back to Baseline Compliance.. -### 3.7 Conversion and Round-Tripping +### 3.8 Conversion and Round-Tripping OpenUSD and robotics XML formats (URDF, SDF, MJCF) are fundamentally mismatched paradigms. Because OpenUSD lacks native schemas for domain-specific data (e.g., URDF , MJCF ), conversions are inherently lossy. Exporters must adhere to the following: * *Payload Resolution:* The active simulation payload (kinematics, inertia, colliders) is the extraction priority. USD composition arcs and instance proxies must be fully baked into explicit geometry and transforms, never discarded. From 8df212194614e8ef667d79158c41188ffaeff3e7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Mon, 23 Mar 2026 12:48:08 +0100 Subject: [PATCH 020/111] feat: add visual geometry LOD VariantSet convention to Section 1.3 MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- rep.md | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/rep.md b/rep.md index 57f39d0..83e88fa 100644 --- a/rep.md +++ b/rep.md @@ -105,6 +105,16 @@ Collision geometries should explicitly specify `purpose="guide"` and `physics:ap 1. **Baseline Approximation (Default Variant):** The default variant must contain "convexHull" or primitive shapes. 2. **Advanced Approximation (Optional Variant):** A secondary variant may contain high-fidelity concave trimeshes intended for Signed Distance Field (SDF) or Hydroelastic collision generation, provided the target simulator supports these paradigms. +#### 1.3.2 Visual Geometry & Level of Detail +Each link's visual and collision scopes should be organized as sibling children (e.g., `/{link}/visual`, `/{link}/collision`). + +To ensure assets function across high-end renderers (Isaac Sim, O3DE), CPU-bound physics simulators (Gazebo, MuJoCo), and lightweight web viewers, assets should provide multiple geometric representations via a `visual_lod` VariantSet on the visual scope: +1. **High (Default Variant):** Full-fidelity source geometry. Suitable for ray-traced rendering and high-end visualization. +2. **Medium (Optional Variant):** Decimated geometry for real-time engines and standard simulation workloads. +3. **Low (Optional Variant):** Aggressively simplified for web viewers, large-scale batch simulation, and GPU-instanced scenes (e.g., Genesis). + +Collision meshes are not subject to visual LOD; their fidelity is governed by the `collision_fidelity` VariantSet (Section 1.3.1). + --- ## 2. ROS 2 Integration Schemas From 407fe1d76787637c88e12f82581d5437610b6112 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Mon, 23 Mar 2026 12:54:17 +0100 Subject: [PATCH 021/111] feat: add asset versioning metadata to Section 3 MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- rep.md | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/rep.md b/rep.md index 83e88fa..5f2ca0a 100644 --- a/rep.md +++ b/rep.md @@ -257,6 +257,19 @@ OpenUSD and robotics XML formats (URDF, SDF, MJCF) are fundamentally mismatched * *API Translation:* Ros2*API schemas must map exclusively to modern extension blocks (e.g., SDF , MJCF ). Obsolete approaches such as injecting legacy 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. +### 3.9 Asset Versioning +USD has no native schema versioning. To prevent silent misinterpretation as this specification evolves, assets must declare their conformance target. + +**Root Prim Metadata (Required):** +* `int rep:versionMajor` — Incremented for breaking changes (new required APIs, layout changes, new restrictions). +* `int rep:versionMinor` — Incremented for additive changes (new optional APIs, relaxed constraints). + +**Root Prim Metadata (Optional):** +* `string rep:authoringTool` — Identifier of the tool that produced the asset (e.g., `"o3de-2405"`, `"urdf2usd-1.2"`). +* `token rep:sourceFormat` — Original format if converted: `"urdf"`, `"sdf"`, `"mjcf"`, `"native"`. + +**Compatibility:** Major version mismatch — consumers must warn, may refuse to load. Minor version mismatch (consumer < asset) — consumers must warn, should load. Minor version mismatch (consumer > asset) — safe. + ## Tools & Reference Implementations A REP XXXX compliance checker is to be developed and shared with the community. The tool will provide validation of all REP recommendations for OpenUSD assets and supply actionable feedback for the user for each divergence. From 5ec34e49e3e61aafa32f9cbc8bfb97ce6f699fd8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Mon, 23 Mar 2026 15:59:29 +0100 Subject: [PATCH 022/111] Updates to section 3 Corrections, removed the version recommendation Signed-off-by: Adam Dabrowski --- rep.md | 33 ++++++++++----------------------- 1 file changed, 10 insertions(+), 23 deletions(-) diff --git a/rep.md b/rep.md index 5f2ca0a..b09d0a3 100644 --- a/rep.md +++ b/rep.md @@ -149,8 +149,8 @@ The root prim of a ROS-interfaced simulation asset may define its context namesp ROS 2 interface schemas (`Ros2TopicAPI`, `Ros2ServiceAPI`, `Ros2ActionAPI`) must be applied to prims according to these placement rules: -* **Robot-wide interfaces** (e.g., `sensor_msgs/msg/JointState` publisher, `control_msgs/action/FollowJointTrajectory` server) must be placed on or under the prim bearing the `Ros2ContextAPI`. These represent aggregate interfaces that span the entire kinematic tree. -* **Sensor interfaces** (e.g., `sensor_msgs/msg/Image` publisher, `sensor_msgs/msg/CameraInfo` publisher) must be placed on the sensor prim — a child Xform of the link the sensor is mounted on. Multiple interfaces for the same sensor (e.g., `image_raw` and `camera_info`) must use separate child prims, one per interface. +* **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 `Ros2ContextAPI`. +* **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 `Ros2*API` schemas are part of the lightweight kinematic/interface graph and must be traversable without loading geometry payloads. ### 2.4 Interface Type Resolution & Naming @@ -230,19 +230,19 @@ Procedural texture graphs (noise generation, math nodes, node graphs) are not in 2. **Mesh primitive variables (Primvars)** such as baked vertex colors using standard USD interpolations. `"vertex"` interpolation is recommended, as `"uniform"` and `"faceVarying"` require converters to split the mesh vertices to comply with glTF’s vertex attribute requirements. ### 3.4 Geometry Constraints -* Collision meshes must be triangulated. Visual meshes may use quad topology, but converters targeting glTF 2.0 must triangulate at export time. -* Non-manifold geometry (open edges, self-intersections) should be repaired at authoring time. Physics engines and web viewers handle non-manifold meshes unpredictably. +* **Triangulation:** Collision meshes must be explicitly triangulated by the author. Visual meshes may use quads or n-gons, but converters targeting glTF 2.0 must triangulate all geometry at export time. +* **Manifold topology:** Collision meshes must be watertight (closed, manifold) and free of self-intersections to ensure stable physics and mass derivation. Non-manifold geometry (e.g., open edges) is strictly limited to purely visual meshes. ### 3.5 Instanceable Leaves (Zero-Copy) Repetitive geometry (bolts, LED arrays on a sensor) must utilize native OpenUSD instancing to minimize memory footprint. Authors must only instance leaf geometry (visuals and colliders), not logical Prims containing PhysicsRigidBodyAPI, Joints, or Ros2*API schemas, as OpenUSD instance proxies obscure child prims from relationship targeting. Authors must use one of two mechanisms to ensure correct glTF conversion: -* *Scenegraph Instancing (`instanceable=true`):* Used for identical structural components (e.g., bolts). Note: The OpenUSD specification requires the prim to compose its geometry via a composition arc (Reference or Payload) for this flag to be valid. Converters must map this to native glTF Node sharing (multiple nodes referencing a single mesh index). -* *Point Instancing (`UsdGeomPointInstancer`):* Used for massive arrays of atomic meshes (e.g., LED grids, warehouse clutter). It scatters a prototype using flat arrays of transforms. Converters must map this directly to the glTF EXT_mesh_gpu_instancing extension. +* **Scenegraph instancing (`instanceable=true`):** Used for identical structural components (e.g., bolts). Note: The OpenUSD specification requires the prim to compose its geometry via a composition arc (Reference or Payload) for this flag to be valid. Converters must map this to native glTF Node sharing (multiple nodes referencing a single mesh index). +* **Point instancing (`UsdGeomPointInstancer`):** Used for massive arrays of atomic meshes (e.g., LED grids, warehouse clutter). It scatters a prototype using flat arrays of transforms. Converters must map this directly to the glTF EXT_mesh_gpu_instancing extension. ### 3.6 Lighting Lighting must be authored using core UsdLux schemas. To ensure deterministic illumination across standard rasterization-based simulators (e.g., Gazebo, MuJoCo, O3DE) and compatibility with web converters, authors must adhere to the following: -* *Punctual lights:* Assets should prioritize standard punctual lights: `UsdLuxDistantLight` (Directional), `UsdLuxSphereLight` (Point), and `UsdLuxSphereLight` modified by the `UsdLuxShapingAPI` (Spot). Converters must map these directly to the glTF `KHR_lights_punctual` extension. -* *Area lights:* Complex area lights (e.g., `UsdLuxRectLight`, `UsdLuxCylinderLight`) lack universal support outside of path-traced engines and should be avoided for interoperable assets. -* *Emissive materials and functional lights:* The `emissiveColor` attribute on a `UsdPreviewSurface` must be used for indicators such as robot status LEDs so the source itself appears bright. However, emissive geometry must not be used for primary scene illumination, as standard simulator rasterizers will not compute their light transport. If a robot component must actively illuminate its surroundings, authors must co-locate a standard `UsdLux` punctual light with the emissive geometry under the same parent `Xform`. The material provides the visible glow of the source, while the paired `UsdLux` prim provides the interoperable scene illumination. +* **Punctual lights:** Assets should prioritize standard punctual lights: `UsdLuxDistantLight` (Directional), `UsdLuxSphereLight` (Point), and `UsdLuxSphereLight` modified by the `UsdLuxShapingAPI` (Spot). Converters must map these directly to the glTF `KHR_lights_punctual` extension. +* **Area lights:** Complex area lights (e.g., `UsdLuxRectLight`, `UsdLuxCylinderLight`) lack universal support outside of path-traced engines and should be avoided for interoperable assets. +* **Emissive materials and functional lights:** The `emissiveColor` attribute on a `UsdPreviewSurface` must be used for indicators such as robot status LEDs so the source itself appears bright. However, emissive geometry must not be used for primary scene illumination, as standard simulator rasterizers will not compute their light transport. If a robot component must actively illuminate its surroundings, authors must co-locate a standard `UsdLux` punctual light with the emissive geometry under the same parent `Xform`. The material provides the visible glow of the source, while the paired `UsdLux` prim provides the interoperable scene illumination. ### 3.7 Variant Baking for Export While OpenUSD natively handles structural variants, many of the simulation tools and formats in the ecosystem don't, including URDF, SDF and glTF 2.0. Due to the burden of implementation, this REP proposes both a baseline and an advanced compliance: @@ -257,21 +257,8 @@ OpenUSD and robotics XML formats (URDF, SDF, MJCF) are fundamentally mismatched * *API Translation:* Ros2*API schemas must map exclusively to modern extension blocks (e.g., SDF , MJCF ). Obsolete approaches such as injecting legacy 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. -### 3.9 Asset Versioning -USD has no native schema versioning. To prevent silent misinterpretation as this specification evolves, assets must declare their conformance target. - -**Root Prim Metadata (Required):** -* `int rep:versionMajor` — Incremented for breaking changes (new required APIs, layout changes, new restrictions). -* `int rep:versionMinor` — Incremented for additive changes (new optional APIs, relaxed constraints). - -**Root Prim Metadata (Optional):** -* `string rep:authoringTool` — Identifier of the tool that produced the asset (e.g., `"o3de-2405"`, `"urdf2usd-1.2"`). -* `token rep:sourceFormat` — Original format if converted: `"urdf"`, `"sdf"`, `"mjcf"`, `"native"`. - -**Compatibility:** Major version mismatch — consumers must warn, may refuse to load. Minor version mismatch (consumer < asset) — consumers must warn, should load. Minor version mismatch (consumer > asset) — safe. - ## Tools & Reference Implementations -A REP XXXX compliance checker is to be developed and shared with the community. The tool will provide validation of all REP recommendations for OpenUSD assets and supply actionable feedback for the user for each divergence. +A REP XXXX compliance checker is to be developed and shared with the community. The tool will provide validation of all REP recommendations for OpenUSD assets and supply actionable feedback for the user for every violation or non-conformance. ## References * **[NVIDIA-ETL-PIPELINE]** NVIDIA, Intrinsic, Disney Research. "Using OpenUSD for Modular and Scalable Robotic Simulation and Development". URL: `https://developer.nvidia.com/blog/using-openusd-for-modular-and-scalable-robotic-simulation-and-development/` From 06da9b797b5bbbddaf1fc805946028b03886b329 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Mon, 23 Mar 2026 16:00:22 +0100 Subject: [PATCH 023/111] Update rep.md Signed-off-by: Adam Dabrowski --- rep.md | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/rep.md b/rep.md index b09d0a3..b007293 100644 --- a/rep.md +++ b/rep.md @@ -40,7 +40,9 @@ The keywords "must", "must not", "required", "shall", "shall not", "should", "sh ## 1. Simulation Assets Baseline -This section confirms and standardizes prior work and recommendations for OpenUSD simulation assets. It draws from the Alliance for OpenUSD (AOUSD), the ASWF USD Working Group, and NVIDIA Asset Requirements. *Note: As AOUSD domain-specific working groups formalize physics and robotics specifications, recommendations in this section are subject to evolution and alignment.* +This section confirms and standardizes prior work and recommendations for OpenUSD simulation assets. It draws from the Alliance for OpenUSD (AOUSD), the ASWF USD Working Group, and NVIDIA Asset Requirements. + +*Note: As AOUSD domain-specific working groups formalize physics and robotics specifications, recommendations in this section are subject to evolution and alignment.* ### 1.1 Coordinate Systems & Units To ensure alignment with ROS standards (REP 103) and stability across solvers: From 7f98ac43b1ad2df8f051853dd43be326d1e9c918 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Mon, 23 Mar 2026 16:17:16 +0100 Subject: [PATCH 024/111] Update rep.md Signed-off-by: Adam Dabrowski --- rep.md | 25 ++++++++++++++----------- 1 file changed, 14 insertions(+), 11 deletions(-) diff --git a/rep.md b/rep.md index b007293..2fb7c82 100644 --- a/rep.md +++ b/rep.md @@ -89,7 +89,7 @@ OpenUSD natively enforces strict naming for Prims (they must start with a letter ### 1.3 Physics & Kinematics * **Rigid Body Hierarchy:** Assets should utilize Logical Nesting to represent kinematic chains (e.g., `Forearm` is a child of `UpperArm`). This preserves the Scene Graph for TF tree generation and ensures compatibility with parsers expecting URDF/SDF-like topologies (e.g., MuJoCo). - * *Simulator Responsibility:* Simulators that require flat hierarchies are responsible for flattening the graph at import time. The asset itself must remain logically nested. + * Simulators that require flat hierarchies are responsible for flattening the graph at import time. The asset itself must remain logically nested. * **Joint Placement:** While `UsdPhysicsJoint` prims rely on relational targeting (`body0` and `body1`) rather than hierarchy, asset authors should place the Joint prim as a sibling adjacent to the child link it connects, within the scope of the parent link. This ensures self-contained modularity. * **Articulation Roots:** A composed simulation stage must contain at most one `PhysicsArticulationRootAPI` per connected kinematic tree. * Assets (e.g., a modular gripper) should be self-contained with an articulation root for standalone use. @@ -197,7 +197,7 @@ Instead, simulators should follow a hybrid implicit/explicit approach for broadc * **Implicit TF Broadcasting (The Asset Tree):** Simulators should automatically infer and broadcast TF frames (using the ROS-validated Prim name) for Prims that represent a ROS interface structure: 1. **The ROS Root:** Any Prim possessing the `Ros2ContextAPI` (often the `base_link`). 2. **Kinematic Chains:** Any Prim possessing a `PhysicsRigidBodyAPI` that is connected (directly or recursively) via a `UsdPhysicsJoint` to a Prim already in the TF tree. This captures robot arms and wheeled bases automatically. - * *Routing Rule:* If the implicit frame is connected to its parent via a `PhysicsFixedJoint`, or has no joint but is rigidly parented in the USD hierarchy, the simulator must broadcast it to `/tf_static`. All movable joint connections must be broadcast to `/tf`. + * **Routing Rule:** If the implicit frame is connected to its parent via a `PhysicsFixedJoint`, or has no joint but is rigidly parented in the USD hierarchy, the simulator must broadcast it to `/tf_static`. All movable joint connections must be broadcast to `/tf`. * Prims bearing only `Ros2TopicAPI`, `Ros2ServiceAPI`, or `Ros2ActionAPI` do not generate TF frames. An interface prim's `frame_id` is determined by its nearest ancestor that is a TF frame (implicit or explicit). * **Explicit TF Broadcasting (`Ros2FrameAPI`):** To publish TFs for non-physical dummy frames (e.g., a kinematic `grasp_point`, a `camera_optical_frame`), asset authors must apply the `Ros2FrameAPI` schema to the target `UsdGeomXform` Prim. @@ -221,15 +221,18 @@ OpenUSD is a vast standard supporting complex features. To guarantee that assets * **Texture Coordinates & UDIMs:** Multi-tile UV mapping (UDIMs) is unsupported by glTF 2.0 and many real-time engines, and must not be used. Unique UVs must be packed strictly into the [0, 1] space (Texture Atlasing). If multiple high-resolution textures are required for a single mesh, authors must partition the geometry using UsdGeomSubset (with `familyName="materialBind"`) and assign separate materials. UV coordinates outside [0, 1] are strictly reserved for seamless tiling textures using repeat wrap modes. ### 3.2 Texture File Formats -Texture assets must use formats portable across USD tooling and glTF export: -* **PNG** or **JPEG** — required as the baseline. These map directly to glTF 2.0 without transcoding. -* **KTX2 (Basis Universal)** — recommended for GPU-compressed textures when targeting real-time viewers, via the `KHR_texture_basisu` glTF extension. -* **EXR, TIFF, and other HDR/DCC formats** must not be used for albedo, normal, or ORM maps in distributed assets. These formats have no glTF pathway and are unsupported by most web viewers. +To ensure native portability across OpenUSD, lightweight simulators, and glTF 2.0, texture formats are constrained: +* **Surface Maps (PNG/JPEG):** 8-bit PNG and JPEG are the only permitted formats for materials. + * **Data Maps:** Normal, Metallic, Roughness, and packed ORM maps must use lossless PNG. JPEG compression artifacts destructively alter PBR math. + * **Color Maps:** BaseColor and Emissive maps may use JPEG to reduce footprint, provided they lack an alpha channel. +* **KTX2** — Treat KTX2 strictly as a downstream glTF export target via `KHR_texture_basisu` glTF extension. Standard OpenUSD lacks native plugins for KTX2. +* **Prohibited formats:** EXR, TIFF, and other HDR/DCC formats must not be used for albedo, normal, or ORM maps in distributed assets. These formats have no glTF pathway and are unsupported by most web viewers. +* **Environment**: As an exception, High Dynamic Range (.hdr) files are permitted only for UsdLuxDomeLight environment maps. ### 3.3 Texture Baking Procedural texture graphs (noise generation, math nodes, node graphs) are not interoperable and must be baked down into explicit data using either: 1. **Image-Backed Textures:** Standard UV-mapped image files routed through standard UsdUVTexture shader nodes. -2. **Mesh primitive variables (Primvars)** such as baked vertex colors using standard USD interpolations. `"vertex"` interpolation is recommended, as `"uniform"` and `"faceVarying"` require converters to split the mesh vertices to comply with glTF’s vertex attribute requirements. +2. **Mesh primitive variables (Primvars)** such as baked vertex colors using standard OpenUSD interpolations. `"vertex"` interpolation is recommended, as `"uniform"` and `"faceVarying"` require converters to split the mesh vertices to comply with glTF’s vertex attribute requirements. ### 3.4 Geometry Constraints * **Triangulation:** Collision meshes must be explicitly triangulated by the author. Visual meshes may use quads or n-gons, but converters targeting glTF 2.0 must triangulate all geometry at export time. @@ -248,14 +251,14 @@ Lighting must be authored using core UsdLux schemas. To ensure deterministic ill ### 3.7 Variant Baking for Export While OpenUSD natively handles structural variants, many of the simulation tools and formats in the ecosystem don't, including URDF, SDF and glTF 2.0. Due to the burden of implementation, this REP proposes both a baseline and an advanced compliance: -* *Baseline compliance:* Converters must export only the active or default variant, destructively discarding all others. This resolved state must be baked by flattening USD composition arcs into a static, logically nested kinematic tree. Never flatten into world-space, as this permanently destroys local joint transforms and ROS TF trees. -* *Advanced compliance (material variants support):* Capable exporters may preserve material variations via the `KHR_materials_variants` extension. Because USD can arbitrarily override granular shader parameters, tools must evaluate each variant state, bake them into distinct glTF Material IDs in memory, and author the swap mapping. -* *Fallback: The glTF extension is invalid if a variant alters underlying mesh topology. If geometry changes, or if the exporter lacks discrete state-evaluation logic, tools must safely fall back to Baseline Compliance.. +* **Baseline compliance:** Converters must export only the active or default variant, destructively discarding all others. This resolved state must be baked by flattening OpenUSD composition arcs into a static, logically nested kinematic tree. Never flatten into world-space, as this permanently destroys local joint transforms and ROS TF trees. +* **Advanced compliance (material variants support):** Capable exporters may preserve material variations via the `KHR_materials_variants` extension. Because OpenUSD can arbitrarily override granular shader parameters, tools must evaluate each variant state, bake them into distinct glTF Material IDs in memory, and author the swap mapping. +* **Fallback:** The glTF extension is invalid if a variant alters underlying mesh topology. If geometry changes, or if the exporter lacks discrete state-evaluation logic, tools must safely fall back to Baseline Compliance.. ### 3.8 Conversion and Round-Tripping OpenUSD and robotics XML formats (URDF, SDF, MJCF) are fundamentally mismatched paradigms. Because OpenUSD lacks native schemas for domain-specific data (e.g., URDF , MJCF ), conversions are inherently lossy. Exporters must adhere to the following: -* *Payload Resolution:* The active simulation payload (kinematics, inertia, colliders) is the extraction priority. USD composition arcs and instance proxies must be fully baked into explicit geometry and transforms, never discarded. +* *Payload Resolution:* The active simulation payload (kinematics, inertia, colliders) is the extraction priority. OpenUSD composition arcs and instance proxies must be fully baked into explicit geometry and transforms, never discarded. * *API Translation:* Ros2*API schemas must map exclusively to modern extension blocks (e.g., SDF , MJCF ). Obsolete approaches such as injecting legacy 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. From f7462d151b165f5411001072f622b5c21f2a316b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Mon, 23 Mar 2026 16:24:34 +0100 Subject: [PATCH 025/111] Update rep.md Signed-off-by: Adam Dabrowski --- rep.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/rep.md b/rep.md index 2fb7c82..44c87e3 100644 --- a/rep.md +++ b/rep.md @@ -111,8 +111,8 @@ Collision geometries should explicitly specify `purpose="guide"` and `physics:ap Each link's visual and collision scopes should be organized as sibling children (e.g., `/{link}/visual`, `/{link}/collision`). To ensure assets function across high-end renderers (Isaac Sim, O3DE), CPU-bound physics simulators (Gazebo, MuJoCo), and lightweight web viewers, assets should provide multiple geometric representations via a `visual_lod` VariantSet on the visual scope: -1. **High (Default Variant):** Full-fidelity source geometry. Suitable for ray-traced rendering and high-end visualization. -2. **Medium (Optional Variant):** Decimated geometry for real-time engines and standard simulation workloads. +1. **Medium (Default Variant):** Decimated geometry for real-time engines and standard simulation workloads. +2. **High (Optional Variant):** Full-fidelity source geometry (e.g. CAD). Suitable for ray-traced rendering and high-end visualization. 3. **Low (Optional Variant):** Aggressively simplified for web viewers, large-scale batch simulation, and GPU-instanced scenes (e.g., Genesis). Collision meshes are not subject to visual LOD; their fidelity is governed by the `collision_fidelity` VariantSet (Section 1.3.1). From 2b813bbdca1045dbed5c4f02b66ea6475b9df791 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Mon, 23 Mar 2026 16:31:47 +0100 Subject: [PATCH 026/111] Update rep.md Signed-off-by: Adam Dabrowski --- rep.md | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/rep.md b/rep.md index 44c87e3..d5668a9 100644 --- a/rep.md +++ b/rep.md @@ -253,14 +253,14 @@ Lighting must be authored using core UsdLux schemas. To ensure deterministic ill While OpenUSD natively handles structural variants, many of the simulation tools and formats in the ecosystem don't, including URDF, SDF and glTF 2.0. Due to the burden of implementation, this REP proposes both a baseline and an advanced compliance: * **Baseline compliance:** Converters must export only the active or default variant, destructively discarding all others. This resolved state must be baked by flattening OpenUSD composition arcs into a static, logically nested kinematic tree. Never flatten into world-space, as this permanently destroys local joint transforms and ROS TF trees. * **Advanced compliance (material variants support):** Capable exporters may preserve material variations via the `KHR_materials_variants` extension. Because OpenUSD can arbitrarily override granular shader parameters, tools must evaluate each variant state, bake them into distinct glTF Material IDs in memory, and author the swap mapping. -* **Fallback:** The glTF extension is invalid if a variant alters underlying mesh topology. If geometry changes, or if the exporter lacks discrete state-evaluation logic, tools must safely fall back to Baseline Compliance.. +* **Fallback:** The glTF extension is invalid if a variant alters underlying mesh topology. If geometry changes, or if the exporter lacks discrete state-evaluation logic, tools must safely fall back to Baseline Compliance. ### 3.8 Conversion and Round-Tripping -OpenUSD and robotics XML formats (URDF, SDF, MJCF) are fundamentally mismatched paradigms. Because OpenUSD lacks native schemas for domain-specific data (e.g., URDF , MJCF ), conversions are inherently lossy. Exporters must adhere to the following: -* *Payload Resolution:* The active simulation payload (kinematics, inertia, colliders) is the extraction priority. OpenUSD composition arcs and instance proxies must be fully baked into explicit geometry and transforms, never discarded. -* *API Translation:* Ros2*API schemas must map exclusively to modern extension blocks (e.g., SDF , MJCF ). Obsolete approaches such as injecting legacy 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. +OpenUSD and robotics XML formats (URDF, SDF, MJCF) are fundamentally mismatched paradigms. Because OpenUSD lacks native schemas for domain-specific data (e.g., URDF ``, MJCF ``), conversions are inherently lossy. Exporters must adhere to the following: +* **Payload Resolution:** The active simulation payload (kinematics, inertia, colliders) is the extraction priority. OpenUSD composition arcs and instance proxies must be fully baked into explicit geometry and transforms, never discarded. +* **API Translation:** Ros2*API schemas must map exclusively to modern extension blocks (e.g., SDF ``, MJCF ``). Obsolete approaches such as injecting legacy `` 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. ## Tools & Reference Implementations A REP XXXX compliance checker is to be developed and shared with the community. The tool will provide validation of all REP recommendations for OpenUSD assets and supply actionable feedback for the user for every violation or non-conformance. @@ -273,7 +273,6 @@ A REP XXXX compliance checker is to be developed and shared with the community. * **[REP-2003]** ROS Enhancement Proposal 2003, "Sensor Data and Map QoS Settings". * **[GLTF-2.0]** Khronos Group, "glTF 2.0 Specification". * **[GLTF-EXT-INSTANCING]** Khronos Group, "EXT_mesh_gpu_instancing Extension Specification". -* **[GLTF-KHR-RIGID]** Khronos Group, "KHR_rigid_bodies Extension Specification" (Draft). ## Copyright This document will be placed in the public domain upon being submitted as PR to a REP proposal by original authors. This text will be changed to "This document is placed in the public domain". From 390819b8578a0c9f85ad0fad5450e0f9d0199592 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Mon, 23 Mar 2026 16:53:44 +0100 Subject: [PATCH 027/111] Update rep.md Signed-off-by: Adam Dabrowski --- rep.md | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/rep.md b/rep.md index d5668a9..14660f7 100644 --- a/rep.md +++ b/rep.md @@ -117,6 +117,12 @@ To ensure assets function across high-end renderers (Isaac Sim, O3DE), CPU-bound Collision meshes are not subject to visual LOD; their fidelity is governed by the `collision_fidelity` VariantSet (Section 1.3.1). +#### 1.3.3 Contact Physics & Materials +To ensure deterministic contact dynamics across engines, authors must bind a `UsdShadeMaterial` bearing the `UsdPhysicsMaterialAPI` to collision geometries. This material must define `physics:staticFriction`, `physics:dynamicFriction`, and `physics:restitution`. To prevent conflicts with visual shading networks, the physical material must be bound to the collision geometry explicitly using the physics material purpose (`material:binding:physics`), rather than the default all-purpose binding.Because engines utilize distinct friction models, converters must approximate these baseline values into their specific representations (e.g., SDF `` or MJCF ``). + +#### 1.4 Safe Extensibility & Vendor Namespacing +Engine-specific parameters (e.g., solver iterations, GPU tensors) not covered by core OpenUSD schemas must be explicitly namespaced with a vendor prefix (e.g., mujoco:, isaac:). This applies to both formal vendor-supplied API schemas and ad-hoc custom attributes. This proprietary metadata must be strictly isolated within the ETL Pipeline's "Proprietary Layer" (Section 2.1) and never authored in the baseline simulation payload. + --- ## 2. ROS 2 Integration Schemas @@ -209,6 +215,9 @@ OpenUSD `UsdPhysics` currently lacks a vendor-neutral (e.g., not `PhysxSchema` o * **Schema Application:** Asset authors must apply the `RoboticsLoopClosureAPI` to any `UsdPhysicsJoint` that closes a kinematic loop. * **Parser Responsibility:** Parsers traversing the `body0`/`body1` relationships to build the kinematic tree must prune their traversal when encountering this schema, handling the joint as a standalone constraint rather than a parent-child hierarchical link. +### 2.10 Optical Frames +OpenUSD cameras natively face the -Z axis, whereas ROS 2 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 Ros2TopicAPI and Ros2FrameAPI schemas must be applied exclusively to this optical frame, ensuring deterministic data orientation in RViz. + --- ## 3. Interoperability and Distribution Profile From 1db35e2268feeeb2d08aa51f081533a6cc5d7c01 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Mon, 23 Mar 2026 17:03:09 +0100 Subject: [PATCH 028/111] Update rep.md Signed-off-by: Adam Dabrowski --- rep.md | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/rep.md b/rep.md index 14660f7..f5fa52c 100644 --- a/rep.md +++ b/rep.md @@ -91,7 +91,7 @@ OpenUSD natively enforces strict naming for Prims (they must start with a letter * **Rigid Body Hierarchy:** Assets should utilize Logical Nesting to represent kinematic chains (e.g., `Forearm` is a child of `UpperArm`). This preserves the Scene Graph for TF tree generation and ensures compatibility with parsers expecting URDF/SDF-like topologies (e.g., MuJoCo). * Simulators that require flat hierarchies are responsible for flattening the graph at import time. The asset itself must remain logically nested. * **Joint Placement:** While `UsdPhysicsJoint` prims rely on relational targeting (`body0` and `body1`) rather than hierarchy, asset authors should place the Joint prim as a sibling adjacent to the child link it connects, within the scope of the parent link. This ensures self-contained modularity. -* **Articulation Roots:** A composed simulation stage must contain at most one `PhysicsArticulationRootAPI` per connected kinematic tree. +* **Articulation Roots:** A composed simulation stage must contain at most one `UsdPhysicsArticulationRootAPI` per connected kinematic tree. * Assets (e.g., a modular gripper) should be self-contained with an articulation root for standalone use. * When composed into a larger kinematic tree, the composing stage should use the OpenUSD list-edit operation `delete apiSchemas = ["PhysicsArticulationRootAPI"]` to prune nested articulation roots. This prevents reduced-coordinate physics solvers from fracturing the robot. * **Loop Closures:** Articulations must form a spanning tree. Joints introducing loop-closing constraints (e.g., parallel linkages) must use the newly introduced `RoboticsLoopClosureAPI` marker schema. @@ -127,9 +127,7 @@ Engine-specific parameters (e.g., solver iterations, GPU tensors) not covered by ## 2. ROS 2 Integration Schemas -Neither OpenUSD nor glTF 2.0 currently standardize the specification of ROS interfaces. This section defines a set of declarative, engine-agnostic API schemas. Simulators are responsible for reading these schemas and generating their respective underlying execution logic. - -A Prim acts as a single logical interface. If a sensor needs multiple interfaces (e.g., `image_raw` and `camera_info`), a child prim for each interface should be utilized. +Neither OpenUSD nor glTF 2.0 currently standardize the specification of ROS interfaces. This section defines a set of declarative, engine-agnostic API schemas (of type `SingleApply`). Simulators are responsible for reading these schemas and generating their respective underlying execution logic. ### 2.1 Schema Isolation and Functional Layering (The ETL Pipeline) @@ -210,6 +208,8 @@ Instead, simulators should follow a hybrid implicit/explicit approach for broadc * `string ros2:frame:id` (Optional): Overrides the TF frame name. If omitted, the validated Prim name is used. * `bool ros2:frame:static` (Optional, Default: `true`): Defines the broadcast destination. If `true`, the simulator must broadcast the frame to `/tf_static` relative to its USD parent. If `false` (e.g., an Xform animated by USD TimeSamples), it must be broadcast to `/tf`. +Note: The broadcast frequency of TF frames is an implementation detail left to the simulator's runtime configuration. + ### 2.9 Kinematic Loop Closures (`RoboticsLoopClosureAPI`) OpenUSD `UsdPhysics` currently lacks a vendor-neutral (e.g., not `PhysxSchema` or `MjcPhysics`) mechanism to identify joints that close a kinematic loop. Because many robotics simulators use reduced-coordinate (e.g., Featherstone) solvers that require strict spanning trees, parsers must know which joint to exclude from the primary tree. * **Schema Application:** Asset authors must apply the `RoboticsLoopClosureAPI` to any `UsdPhysicsJoint` that closes a kinematic loop. From 1d2b6104d8824ff57229d1b212e886590d0e31e8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Mon, 23 Mar 2026 17:15:18 +0100 Subject: [PATCH 029/111] Update rep.md Signed-off-by: Adam Dabrowski --- rep.md | 76 ++++++++++++++++++++++++++++++---------------------------- 1 file changed, 39 insertions(+), 37 deletions(-) diff --git a/rep.md b/rep.md index f5fa52c..8d6735c 100644 --- a/rep.md +++ b/rep.md @@ -57,12 +57,29 @@ To ensure alignment with ROS standards (REP 103) and stability across solvers: ### 1.2 Asset Structure & Composition This REP adopts the ASWF Guidelines for Structuring USD Assets. -#### 1.2.1 The Composition Model +#### 1.2.1 Schema Isolation and Functional Layering (The ETL Pipeline) + +To avoid "Unknown Schema" errors in standard 3D authoring tools (e.g., Blender, Maya) and to ensure assets remain modular, functional layering (Extract-Transform-Load) should be utilized for ROS 2 interfaces, physics, and simulator-specific tooling syntax. + +This REP endorses the ETL composition architecture developed collaboratively by NVIDIA, Intrinsic, and Disney Research for OpenUSD robotics assets. + +![Extract-Transform-Load Pipeline for Robots in USD](etl_pipeline_diagram.png) +*Figure 1: The Extract-Transform-Load (ETL) composition pipeline for OpenUSD robotics assets. Source: [NVIDIA Developer Blog](https://developer.nvidia.com/blog/using-openusd-for-modular-and-scalable-robotic-simulation-and-development/)* + +As illustrated in Figure 1, assets should be divided into functional layers composed via References and Payloads: + +* **Asset Source & Transformation (The Base Layer):** The raw CAD data (`asset_base.usd`) is optimized into simulation-ready geometry (`asset_sim_optimized.usd`). This layer contains native OpenUSD schemas (`UsdGeom`, `UsdShade`). +* **Features (The Domain-Specific Layers):** Domain metadata is isolated into specific overlay files that reference the Base Layer. For example, `asset_physics.usd` contains the rigid bodies and joints, while `asset_ros.usd` contains the `Ros2*API` schemas defined in this REP. +* **Entry Point (`asset.usd`):** The final distributed asset is a lightweight interface layer that uses **Payloads** to load the Features. +* **Proprietary Layer:** Asset authors should avoid including heavy, simulator-specific implementations (e.g., proprietary execution graphs) within the interoperable asset package. If unavoidable, they must minimize this proprietary layer (e.g., `asset_isaac.usd`) to what is strictly necessary and keep it isolated as a separate Feature layer. + + +#### 1.2.2 The Composition Model * **Components:** Atomic assets (e.g., a `LidarSensor`, a `Box`) must have `kind="component"` on their root prim. * **Assemblies:** Aggregates (e.g., a `Warehouse` containing racks) must have `kind="assembly"` or `kind="group"`. * A `component` must not contain another `component`: if finer organizational granularity is required, authors must use kind="subcomponent" allowing converters to easily identify the "atomic units" of the scene. -#### 1.2.2 Composition Arcs (LIVRPS Constraints) +#### 1.2.3 Composition Arcs (LIVRPS Constraints) To guarantee that simulation assets remain self-contained, portable, and predictable across different simulator parsers, asset authors must adhere to the following constraints regarding OpenUSD's LIVRPS composition arcs: * **[L] Local:** Primary authoring of overrides and properties on the asset is fully supported. * **[I] Inherits & [S] Specializes:** Asset authors should not rely on `Inherits` or `Specializes` arcs for core robot kinematics, physics APIs, or ROS schemas when distributing standalone assets. These arcs create hard dependencies on external class hierarchies; if a simulator's environment lacks the base class definitions, the asset will fail to parse correctly. @@ -72,18 +89,18 @@ To guarantee that simulation assets remain self-contained, portable, and predict * Payloads must not gate joint or link prims themselves. The kinematic topology (Prims bearing `PhysicsRigidBodyAPI`, `PhysicsJoint` schemas, and `Ros2*API` schemas) must reside in the primarily loaded scene graph (e.g., via Local authoring or standard References). * The Payload should solely encapsulate the nested geometric and material data. This enables ROS parsers and web converters to traverse the lightweight kinematic tree efficiently without loading heavy buffers. -#### 1.2.3 Variants and Reusability +#### 1.2.4 Variants and Reusability OpenUSD `VariantSets` are the normative mechanism for asset reusability (e.g., encapsulating multiple furniture styles, different robot end-effectors, or optional sensor suites within a single asset). * **Default Variant Fallback:** Any asset utilizing `VariantSets` must author a default variant selection. This ensures that if the asset is loaded by a simulator or CI/CD pipeline without explicit variant overrides, it resolves to a valid, predictable physical and visual state. * **ROS Interface Resolution:** A change in a variant selection may add or remove Prims containing `Ros2*API` schemas (e.g., swapping a generic robot head for a sensor-equipped head). Simulators and tooling must only evaluate and spawn ROS interfaces that are active within the currently resolved variant state of the stage. -#### 1.2.4 Asset Management & FileFormat Plugins +#### 1.2.5 Asset Management & FileFormat Plugins * **Path Resolution:** Internal references must use relative paths (`./geo/mesh.usdc`). For distributed, highly interoperable assets, all file dependencies should be self-contained and rely exclusively on relative paths. * **ROS packages:** External dependencies to other ROS packages must use the package:// URI scheme, and should be contained in ROS-specific .usd files in the ETL pipeline. Asset authors must be aware that resolving these URIs requires the host simulator or tool to implement a custom OpenUSD ArResolver plugin. Absolute paths and proprietary schemes (e.g., omniverse://) are strictly prohibited in distributed assets. * **Native Composition vs. Custom Prefabs:** The use of custom or vendor-specific string attributes (e.g., `custom string my_sim:prefabPath = "robot.usd"`) to dynamically load, instantiate, or compose assets at runtime is strictly prohibited for interoperable assets. Asset composition must rely purely on native OpenUSD references or payloads. * **FileFormat Plugins:** OpenUSD supports FileFormat plugins (e.g., MuJoCo's `usdMjcf` plugin) to dynamically translate legacy formats into USD stages at runtime. While these plugins are recommended for import pathways, this REP governs the *resulting in-memory OpenUSD data*. Plugins interfacing with the ROS 2 ecosystem must generate stages that conform to the physical hierarchies and API schemas defined in this document. -#### 1.2.5 ROS-Compatible Identifiers +#### 1.2.6 ROS-Compatible Identifiers OpenUSD natively enforces strict naming for Prims (they must start with a letter or underscore, followed by alphanumeric characters or underscores: [a-zA-Z_][a-zA-Z0-9_]*). This natively aligns with ROS conventions. Furthermore, Prim names intended to map directly to ROS TF Frames must not contain spaces or special characters that could violate downstream ROS 2 lexical rules. ### 1.3 Physics & Kinematics @@ -118,10 +135,16 @@ To ensure assets function across high-end renderers (Isaac Sim, O3DE), CPU-bound Collision meshes are not subject to visual LOD; their fidelity is governed by the `collision_fidelity` VariantSet (Section 1.3.1). #### 1.3.3 Contact Physics & Materials -To ensure deterministic contact dynamics across engines, authors must bind a `UsdShadeMaterial` bearing the `UsdPhysicsMaterialAPI` to collision geometries. This material must define `physics:staticFriction`, `physics:dynamicFriction`, and `physics:restitution`. To prevent conflicts with visual shading networks, the physical material must be bound to the collision geometry explicitly using the physics material purpose (`material:binding:physics`), rather than the default all-purpose binding.Because engines utilize distinct friction models, converters must approximate these baseline values into their specific representations (e.g., SDF `` or MJCF ``). +To ensure deterministic contact dynamics across engines, authors must bind a `UsdShadeMaterial` bearing the `UsdPhysicsMaterialAPI` to collision geometries. This material must define `physics:staticFriction`, `physics:dynamicFriction`, and `physics:restitution`. To prevent conflicts with visual shading networks, the physical material must be bound to the collision geometry explicitly using the physics material purpose (`material:binding:physics`), rather than the default all-purpose binding. Because engines utilize distinct friction models, converters must approximate these baseline values into their specific representations (e.g., SDF `` or MJCF ``). + +### 1.3.4 Kinematic Loop Closures (`RoboticsLoopClosureAPI`) +OpenUSD `UsdPhysics` currently lacks a vendor-neutral (e.g., not `PhysxSchema` or `MjcPhysics`) mechanism to identify joints that close a kinematic loop. Because many robotics simulators use reduced-coordinate (e.g., Featherstone) solvers that require strict spanning trees, parsers must know which joint to exclude from the primary tree. +* **Schema Application:** Asset authors must apply the `RoboticsLoopClosureAPI` to any `UsdPhysicsJoint` that closes a kinematic loop. +* **Parser Responsibility:** Parsers traversing the `body0`/`body1` relationships to build the kinematic tree must prune their traversal when encountering this schema, handling the joint as a standalone constraint rather than a parent-child hierarchical link. -#### 1.4 Safe Extensibility & Vendor Namespacing -Engine-specific parameters (e.g., solver iterations, GPU tensors) not covered by core OpenUSD schemas must be explicitly namespaced with a vendor prefix (e.g., mujoco:, isaac:). This applies to both formal vendor-supplied API schemas and ad-hoc custom attributes. This proprietary metadata must be strictly isolated within the ETL Pipeline's "Proprietary Layer" (Section 2.1) and never authored in the baseline simulation payload. + +### 1.4 Safe Extensibility & Vendor Namespacing +Engine-specific parameters (e.g., solver iterations, GPU tensors) not covered by core OpenUSD schemas must be explicitly namespaced with a vendor prefix (e.g., mujoco:, isaac:). This applies to both formal vendor-supplied API schemas and ad-hoc custom attributes. This proprietary metadata must be strictly isolated within the ETL Pipeline's "Proprietary Layer" (Section 1.2.1) and never authored in the baseline simulation payload. --- @@ -129,29 +152,13 @@ Engine-specific parameters (e.g., solver iterations, GPU tensors) not covered by Neither OpenUSD nor glTF 2.0 currently standardize the specification of ROS interfaces. This section defines a set of declarative, engine-agnostic API schemas (of type `SingleApply`). Simulators are responsible for reading these schemas and generating their respective underlying execution logic. -### 2.1 Schema Isolation and Functional Layering (The ETL Pipeline) - -To avoid "Unknown Schema" errors in standard 3D authoring tools (e.g., Blender, Maya) and to ensure assets remain modular, functional layering (Extract-Transform-Load) should be utilized for ROS 2 interfaces, physics, and simulator-specific tooling syntax. - -This REP endorses the ETL composition architecture developed collaboratively by NVIDIA, Intrinsic, and Disney Research for OpenUSD robotics assets. - -![Extract-Transform-Load Pipeline for Robots in USD](etl_pipeline_diagram.png) -*Figure 1: The Extract-Transform-Load (ETL) composition pipeline for OpenUSD robotics assets. Source: [NVIDIA Developer Blog](https://developer.nvidia.com/blog/using-openusd-for-modular-and-scalable-robotic-simulation-and-development/)* - -As illustrated in Figure 1, assets should be divided into functional layers composed via References and Payloads: - -* **Asset Source & Transformation (The Base Layer):** The raw CAD data (`asset_base.usd`) is optimized into simulation-ready geometry (`asset_sim_optimized.usd`). This layer contains native OpenUSD schemas (`UsdGeom`, `UsdShade`). -* **Features (The Domain-Specific Layers):** Domain metadata is isolated into specific overlay files that reference the Base Layer. For example, `asset_physics.usd` contains the rigid bodies and joints, while `asset_ros.usd` contains the `Ros2*API` schemas defined in this REP. -* **Entry Point (`asset.usd`):** The final distributed asset is a lightweight interface layer that uses **Payloads** to load the Features. -* **Proprietary Layer:** Asset authors should avoid including heavy, simulator-specific implementations (e.g., proprietary execution graphs) within the interoperable asset package. If unavoidable, they must minimize this proprietary layer (e.g., `asset_isaac.usd`) to what is strictly necessary and keep it isolated as a separate Feature layer. - -### 2.2 The ROS 2 Context (`Ros2ContextAPI`) +### 2.1 The ROS 2 Context (`Ros2ContextAPI`) The root prim of a ROS-interfaced simulation asset may define its context namespace. * `string ros2:context:namespace`: Prefixes all topics within this scope (e.g., `/robot_1`). The namespace is additive in the asset hierarchy and with a top-level namespace set during simulation deployment (e.g., via the `SpawnEntity` service). * `int ros2:context:domain_id` (Optional): Overrides the default ROS Domain ID for interfaces descending from this context. * `string ros2:context:parent_frame` (Optional, Default: `"world"`): Defines the parent `frame_id` used when the simulator broadcasts the ground-truth transform of this context's root prim. It is only valid for the top-most context in the resolved USD Stage and ignored otherwise. -### 2.3 Interface Placement +### 2.2 Interface Placement ROS 2 interface schemas (`Ros2TopicAPI`, `Ros2ServiceAPI`, `Ros2ActionAPI`) must be applied to prims according to these placement rules: @@ -159,12 +166,12 @@ ROS 2 interface schemas (`Ros2TopicAPI`, `Ros2ServiceAPI`, `Ros2ActionAPI`) must * **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 `Ros2*API` schemas are part of the lightweight kinematic/interface graph and must be traversable without loading geometry payloads. -### 2.4 Interface Type Resolution & Naming +### 2.3 Interface Type Resolution & Naming For all schema types (Topics, Services, Actions) defined below: * **Type Resolution:** Tooling and compliant simulators must attempt to resolve the `ros2:*:type` string (e.g., `sensor_msgs/msg/Image`) dynamically against the sourced ROS 2 environment. If the interface type is not found, the simulator must safely disable that specific interface, allow the rest of the asset to function normally, and emit a distinct warning/error. * **Name Validation:** All `ros2:*:name` values must strictly adhere to ROS 2 topic naming rules (alphanumeric, underscores, and forward slashes only; cannot start with a number). -### 2.5 Topic Interface (`Ros2TopicAPI`) +### 2.4 Topic Interface (`Ros2TopicAPI`) Applies to Prims that exchange streaming ROS data. **Core Attributes (Required):** @@ -181,19 +188,19 @@ Maps directly to `rmw_qos_profile_t` policies. If an attribute is omitted, simul * `token ros2:topic:qos:history`: Values: `["system_default", "keep_last", "keep_all"]`. (Default: `"system_default"`). * `int ros2:topic:qos:depth`: Queue size. Evaluated only when history is `keep_last`. (Default: `10`). -### 2.6 Service Interface (`Ros2ServiceAPI`) +### 2.5 Service Interface (`Ros2ServiceAPI`) Applies to Prims handling synchronous requests (e.g., resetting an environment). * `token ros2:service:role`: Values: `["server", "client"]`. (Simulation assets are typically `server`). * `string ros2:service:name`: The service name. * `string ros2:service:type`: The service type (e.g., `std_srvs/srv/SetBool`). -### 2.7 Action Interface (`Ros2ActionAPI`) +### 2.6 Action Interface (`Ros2ActionAPI`) Applies to Prims handling asynchronous, long-running behaviors. * `token ros2:action:role`: Values: `["server", "client"]`. (Simulation assets are typically `server`). * `string ros2:action:name`: The action name. * `string ros2:action:type`: The action type (e.g., `control_msgs/action/FollowJointTrajectory`). -### 2.8 Frame Publishing and TF2 (`Ros2FrameAPI`) +### 2.7 Frame Publishing and TF2 (`Ros2FrameAPI`) Mapping a deeply nested OpenUSD scene graph directly to a ROS 2 TF tree can cause significant performance overhead. To prevent flooding the `/tf` topic with generic physical props (e.g., warehouse boxes), compliant simulators should not broadcast transforms for every `PhysicsRigidBodyAPI`. Instead, simulators should follow a hybrid implicit/explicit approach for broadcasting `tf2` transforms: @@ -210,12 +217,7 @@ Instead, simulators should follow a hybrid implicit/explicit approach for broadc Note: The broadcast frequency of TF frames is an implementation detail left to the simulator's runtime configuration. -### 2.9 Kinematic Loop Closures (`RoboticsLoopClosureAPI`) -OpenUSD `UsdPhysics` currently lacks a vendor-neutral (e.g., not `PhysxSchema` or `MjcPhysics`) mechanism to identify joints that close a kinematic loop. Because many robotics simulators use reduced-coordinate (e.g., Featherstone) solvers that require strict spanning trees, parsers must know which joint to exclude from the primary tree. -* **Schema Application:** Asset authors must apply the `RoboticsLoopClosureAPI` to any `UsdPhysicsJoint` that closes a kinematic loop. -* **Parser Responsibility:** Parsers traversing the `body0`/`body1` relationships to build the kinematic tree must prune their traversal when encountering this schema, handling the joint as a standalone constraint rather than a parent-child hierarchical link. - -### 2.10 Optical Frames +### 2.8 Optical Frames OpenUSD cameras natively face the -Z axis, whereas ROS 2 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 Ros2TopicAPI and Ros2FrameAPI schemas must be applied exclusively to this optical frame, ensuring deterministic data orientation in RViz. --- From 2b67b8131d1a07bc21c7171addff2d87cf59b195 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Mon, 23 Mar 2026 17:20:52 +0100 Subject: [PATCH 030/111] Update rep.md Signed-off-by: Adam Dabrowski --- rep.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rep.md b/rep.md index 8d6735c..87000ae 100644 --- a/rep.md +++ b/rep.md @@ -144,7 +144,7 @@ OpenUSD `UsdPhysics` currently lacks a vendor-neutral (e.g., not `PhysxSchema` o ### 1.4 Safe Extensibility & Vendor Namespacing -Engine-specific parameters (e.g., solver iterations, GPU tensors) not covered by core OpenUSD schemas must be explicitly namespaced with a vendor prefix (e.g., mujoco:, isaac:). This applies to both formal vendor-supplied API schemas and ad-hoc custom attributes. This proprietary metadata must be strictly isolated within the ETL Pipeline's "Proprietary Layer" (Section 1.2.1) and never authored in the baseline simulation payload. +Engine-specific parameters (e.g., solver iterations, GPU tensors) not covered by core OpenUSD schemas must be explicitly namespaced with a vendor prefix (e.g., mujoco:, isaac:). This applies to both formal vendor-supplied API schemas and ad-hoc custom attributes. This proprietary metadata must be strictly isolated within the ETL Pipeline's "Proprietary Layer" (Section 1.2.1) and never authored in the baseline simulation payload. Authors must strive to minimize proprietary layer to strictly necessary. --- From 7c9cf22638ccfb9ff1316a37501c009096f31d3c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Mon, 23 Mar 2026 17:27:25 +0100 Subject: [PATCH 031/111] Update rep.md Signed-off-by: Adam Dabrowski --- rep.md | 1 + 1 file changed, 1 insertion(+) diff --git a/rep.md b/rep.md index 87000ae..9628408 100644 --- a/rep.md +++ b/rep.md @@ -108,6 +108,7 @@ OpenUSD natively enforces strict naming for Prims (they must start with a letter * **Rigid Body Hierarchy:** Assets should utilize Logical Nesting to represent kinematic chains (e.g., `Forearm` is a child of `UpperArm`). This preserves the Scene Graph for TF tree generation and ensures compatibility with parsers expecting URDF/SDF-like topologies (e.g., MuJoCo). * Simulators that require flat hierarchies are responsible for flattening the graph at import time. The asset itself must remain logically nested. * **Joint Placement:** While `UsdPhysicsJoint` prims rely on relational targeting (`body0` and `body1`) rather than hierarchy, asset authors should place the Joint prim as a sibling adjacent to the child link it connects, within the scope of the parent link. This ensures self-contained modularity. +* **Joint Limits:** Non-continuous joints (e.g., revolute, prismatic) must author explicit `physics:lowerLimit` and `physics:upperLimit` attributes. * **Articulation Roots:** A composed simulation stage must contain at most one `UsdPhysicsArticulationRootAPI` per connected kinematic tree. * Assets (e.g., a modular gripper) should be self-contained with an articulation root for standalone use. * When composed into a larger kinematic tree, the composing stage should use the OpenUSD list-edit operation `delete apiSchemas = ["PhysicsArticulationRootAPI"]` to prune nested articulation roots. This prevents reduced-coordinate physics solvers from fracturing the robot. From 246cdf6bb40e57bb0049f8b5f59b6343c01acddf Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Mon, 23 Mar 2026 17:54:31 +0100 Subject: [PATCH 032/111] Update rep.md Signed-off-by: Adam Dabrowski --- rep.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rep.md b/rep.md index 9628408..1a1b941 100644 --- a/rep.md +++ b/rep.md @@ -190,7 +190,7 @@ Maps directly to `rmw_qos_profile_t` policies. If an attribute is omitted, simul * `int ros2:topic:qos:depth`: Queue size. Evaluated only when history is `keep_last`. (Default: `10`). ### 2.5 Service Interface (`Ros2ServiceAPI`) -Applies to Prims handling synchronous requests (e.g., resetting an environment). +Applies to Prims handling synchronous requests (e.g., blinking lights). * `token ros2:service:role`: Values: `["server", "client"]`. (Simulation assets are typically `server`). * `string ros2:service:name`: The service name. * `string ros2:service:type`: The service type (e.g., `std_srvs/srv/SetBool`). From fc6dc7a1407db27a98d6edd697f7a288fe613664 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Mon, 23 Mar 2026 18:37:15 +0100 Subject: [PATCH 033/111] Update rep.md Added point about parallel scenes (for RL, e.g. Genesis) Signed-off-by: Adam Dabrowski --- rep.md | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/rep.md b/rep.md index 1a1b941..43bf653 100644 --- a/rep.md +++ b/rep.md @@ -103,6 +103,11 @@ OpenUSD `VariantSets` are the normative mechanism for asset reusability (e.g., e #### 1.2.6 ROS-Compatible Identifiers OpenUSD natively enforces strict naming for Prims (they must start with a letter or underscore, followed by alphanumeric characters or underscores: [a-zA-Z_][a-zA-Z0-9_]*). This natively aligns with ROS conventions. Furthermore, Prim names intended to map directly to ROS TF Frames must not contain spaces or special characters that could violate downstream ROS 2 lexical rules. +#### 1.2.7 Parallel Simulation and Instancing +OpenUSD's native instancing mechanisms are designed for repetitive visual and structural geometry. They must not be used to clone articulated physics assets to create massive parallel arrays (e.g., for reinforcement learning). +* **Canonical Assets:** Authors must distribute a single, self-contained canonical environment. +* **Runtime Delegation:** Simulators supporting massive parallelism are expected to handle environment replication natively at runtime via their own APIs. Authors must not bake thousands of physics-enabled clones into the source file. + ### 1.3 Physics & Kinematics * **Rigid Body Hierarchy:** Assets should utilize Logical Nesting to represent kinematic chains (e.g., `Forearm` is a child of `UpperArm`). This preserves the Scene Graph for TF tree generation and ensures compatibility with parsers expecting URDF/SDF-like topologies (e.g., MuJoCo). From 233d61d6cee62ec3b892a0705a78bed17179730d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Mon, 23 Mar 2026 18:49:01 +0100 Subject: [PATCH 034/111] Update rep.md Clarified naming of chapters Signed-off-by: Adam Dabrowski --- rep.md | 27 +++++++++++++-------------- 1 file changed, 13 insertions(+), 14 deletions(-) diff --git a/rep.md b/rep.md index 43bf653..02d518b 100644 --- a/rep.md +++ b/rep.md @@ -89,12 +89,12 @@ To guarantee that simulation assets remain self-contained, portable, and predict * Payloads must not gate joint or link prims themselves. The kinematic topology (Prims bearing `PhysicsRigidBodyAPI`, `PhysicsJoint` schemas, and `Ros2*API` schemas) must reside in the primarily loaded scene graph (e.g., via Local authoring or standard References). * The Payload should solely encapsulate the nested geometric and material data. This enables ROS parsers and web converters to traverse the lightweight kinematic tree efficiently without loading heavy buffers. -#### 1.2.4 Variants and Reusability +#### 1.2.4 Variants OpenUSD `VariantSets` are the normative mechanism for asset reusability (e.g., encapsulating multiple furniture styles, different robot end-effectors, or optional sensor suites within a single asset). * **Default Variant Fallback:** Any asset utilizing `VariantSets` must author a default variant selection. This ensures that if the asset is loaded by a simulator or CI/CD pipeline without explicit variant overrides, it resolves to a valid, predictable physical and visual state. * **ROS Interface Resolution:** A change in a variant selection may add or remove Prims containing `Ros2*API` schemas (e.g., swapping a generic robot head for a sensor-equipped head). Simulators and tooling must only evaluate and spawn ROS interfaces that are active within the currently resolved variant state of the stage. -#### 1.2.5 Asset Management & FileFormat Plugins +#### 1.2.5 Asset Management * **Path Resolution:** Internal references must use relative paths (`./geo/mesh.usdc`). For distributed, highly interoperable assets, all file dependencies should be self-contained and rely exclusively on relative paths. * **ROS packages:** External dependencies to other ROS packages must use the package:// URI scheme, and should be contained in ROS-specific .usd files in the ETL pipeline. Asset authors must be aware that resolving these URIs requires the host simulator or tool to implement a custom OpenUSD ArResolver plugin. Absolute paths and proprietary schemes (e.g., omniverse://) are strictly prohibited in distributed assets. * **Native Composition vs. Custom Prefabs:** The use of custom or vendor-specific string attributes (e.g., `custom string my_sim:prefabPath = "robot.usd"`) to dynamically load, instantiate, or compose assets at runtime is strictly prohibited for interoperable assets. Asset composition must rely purely on native OpenUSD references or payloads. @@ -108,8 +108,7 @@ OpenUSD's native instancing mechanisms are designed for repetitive visual and st * **Canonical Assets:** Authors must distribute a single, self-contained canonical environment. * **Runtime Delegation:** Simulators supporting massive parallelism are expected to handle environment replication natively at runtime via their own APIs. Authors must not bake thousands of physics-enabled clones into the source file. -### 1.3 Physics & Kinematics - +### 1.3 Physics * **Rigid Body Hierarchy:** Assets should utilize Logical Nesting to represent kinematic chains (e.g., `Forearm` is a child of `UpperArm`). This preserves the Scene Graph for TF tree generation and ensures compatibility with parsers expecting URDF/SDF-like topologies (e.g., MuJoCo). * Simulators that require flat hierarchies are responsible for flattening the graph at import time. The asset itself must remain logically nested. * **Joint Placement:** While `UsdPhysicsJoint` prims rely on relational targeting (`body0` and `body1`) rather than hierarchy, asset authors should place the Joint prim as a sibling adjacent to the child link it connects, within the scope of the parent link. This ensures self-contained modularity. @@ -125,12 +124,12 @@ OpenUSD's native instancing mechanisms are designed for repetitive visual and st * *Dummy Frames:* Non-physical dummy frames (e.g., `camera_optical_frame`) must not possess a `PhysicsRigidBodyAPI`. They should be tracked using the `Ros2FrameAPI` as defined in Section 2.8. * **Inertia Representation:** Unlike URDF and SDFormat's 6-value symmetric matrix, OpenUSD requires an eigendecomposed inertia tensor. Converters must mathematically decompose the source matrix into physics:diagonalInertia (eigenvalues) and physics:principalAxes (quaternion). This native decomposed form is the strict single source of truth; custom 6-value array attributes must not be authored or parsed. -#### 1.3.1 Collisions & The Dual-Fidelity Pattern +#### 1.3.1 Collisions Collision geometries should explicitly specify `purpose="guide"` and `physics:approximation="none"`. To ensure assets function across both standard physics engines and advanced contact-rich solvers (e.g., Newton), assets should employ a "Dual-Fidelity Pattern" utilizing a `collision_fidelity` OpenUSD `VariantSet`: 1. **Baseline Approximation (Default Variant):** The default variant must contain "convexHull" or primitive shapes. 2. **Advanced Approximation (Optional Variant):** A secondary variant may contain high-fidelity concave trimeshes intended for Signed Distance Field (SDF) or Hydroelastic collision generation, provided the target simulator supports these paradigms. -#### 1.3.2 Visual Geometry & Level of Detail +#### 1.3.2 Level of Detail Each link's visual and collision scopes should be organized as sibling children (e.g., `/{link}/visual`, `/{link}/collision`). To ensure assets function across high-end renderers (Isaac Sim, O3DE), CPU-bound physics simulators (Gazebo, MuJoCo), and lightweight web viewers, assets should provide multiple geometric representations via a `visual_lod` VariantSet on the visual scope: @@ -140,7 +139,7 @@ To ensure assets function across high-end renderers (Isaac Sim, O3DE), CPU-bound Collision meshes are not subject to visual LOD; their fidelity is governed by the `collision_fidelity` VariantSet (Section 1.3.1). -#### 1.3.3 Contact Physics & Materials +#### 1.3.3 Contact Physics To ensure deterministic contact dynamics across engines, authors must bind a `UsdShadeMaterial` bearing the `UsdPhysicsMaterialAPI` to collision geometries. This material must define `physics:staticFriction`, `physics:dynamicFriction`, and `physics:restitution`. To prevent conflicts with visual shading networks, the physical material must be bound to the collision geometry explicitly using the physics material purpose (`material:binding:physics`), rather than the default all-purpose binding. Because engines utilize distinct friction models, converters must approximate these baseline values into their specific representations (e.g., SDF `` or MJCF ``). ### 1.3.4 Kinematic Loop Closures (`RoboticsLoopClosureAPI`) @@ -149,7 +148,7 @@ OpenUSD `UsdPhysics` currently lacks a vendor-neutral (e.g., not `PhysxSchema` o * **Parser Responsibility:** Parsers traversing the `body0`/`body1` relationships to build the kinematic tree must prune their traversal when encountering this schema, handling the joint as a standalone constraint rather than a parent-child hierarchical link. -### 1.4 Safe Extensibility & Vendor Namespacing +### 1.4 Isolation of vendor-specific extensions Engine-specific parameters (e.g., solver iterations, GPU tensors) not covered by core OpenUSD schemas must be explicitly namespaced with a vendor prefix (e.g., mujoco:, isaac:). This applies to both formal vendor-supplied API schemas and ad-hoc custom attributes. This proprietary metadata must be strictly isolated within the ETL Pipeline's "Proprietary Layer" (Section 1.2.1) and never authored in the baseline simulation payload. Authors must strive to minimize proprietary layer to strictly necessary. --- @@ -172,7 +171,7 @@ ROS 2 interface schemas (`Ros2TopicAPI`, `Ros2ServiceAPI`, `Ros2ActionAPI`) must * **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 `Ros2*API` schemas are part of the lightweight kinematic/interface graph and must be traversable without loading geometry payloads. -### 2.3 Interface Type Resolution & Naming +### 2.3 Interface Resolution For all schema types (Topics, Services, Actions) defined below: * **Type Resolution:** Tooling and compliant simulators must attempt to resolve the `ros2:*:type` string (e.g., `sensor_msgs/msg/Image`) dynamically against the sourced ROS 2 environment. If the interface type is not found, the simulator must safely disable that specific interface, allow the rest of the asset to function normally, and emit a distinct warning/error. * **Name Validation:** All `ros2:*:name` values must strictly adhere to ROS 2 topic naming rules (alphanumeric, underscores, and forward slashes only; cannot start with a number). @@ -186,7 +185,7 @@ Applies to Prims that exchange streaming ROS data. * `string ros2:topic:type`: The ROS message type. * `double ros2:topic:publish_rate`: Target publication frequency in Hz. Required for publishers; ignored for subscriptions. -**Quality of Service (QoS) Attributes:** +**Quality of Service (QoS):** Maps directly to `rmw_qos_profile_t` policies. If an attribute is omitted, simulators must assume the specified defaults. *(Note: As per REP 2003, simulated sensors should default to `"system_default"` which maps to best-effort, while map publishers should use `"transient_local"`).* * `bool ros2:topic:qos:match_publisher` (Optional, Default: `false`). For subscriptions only. If `true`, the simulator bridge must attempt to use ROS 2 QoS matching to adapt to the discovered publisher, ignoring explicit reliability/durability settings. * `token ros2:topic:qos:reliability`: Values: `["system_default", "reliable", "best_effort"]`. (Default: `"system_default"`). @@ -228,7 +227,7 @@ OpenUSD cameras natively face the -Z axis, whereas ROS 2 optical frames (REP 103 --- -## 3. Interoperability and Distribution Profile +## 3. Export and Conversion OpenUSD is a vast standard supporting complex features. To guarantee that assets can be distributed, viewed in desktop tools (e.g., `usdview`) or lightweight web tools (e.g., Foxglove, Webviz, Rerun), and successfully converted to glTF 2.0, assets must adhere to this constrained subset. @@ -255,7 +254,7 @@ Procedural texture graphs (noise generation, math nodes, node graphs) are not in * **Triangulation:** Collision meshes must be explicitly triangulated by the author. Visual meshes may use quads or n-gons, but converters targeting glTF 2.0 must triangulate all geometry at export time. * **Manifold topology:** Collision meshes must be watertight (closed, manifold) and free of self-intersections to ensure stable physics and mass derivation. Non-manifold geometry (e.g., open edges) is strictly limited to purely visual meshes. -### 3.5 Instanceable Leaves (Zero-Copy) +### 3.5 Instanceable Leaves Repetitive geometry (bolts, LED arrays on a sensor) must utilize native OpenUSD instancing to minimize memory footprint. Authors must only instance leaf geometry (visuals and colliders), not logical Prims containing PhysicsRigidBodyAPI, Joints, or Ros2*API schemas, as OpenUSD instance proxies obscure child prims from relationship targeting. Authors must use one of two mechanisms to ensure correct glTF conversion: * **Scenegraph instancing (`instanceable=true`):** Used for identical structural components (e.g., bolts). Note: The OpenUSD specification requires the prim to compose its geometry via a composition arc (Reference or Payload) for this flag to be valid. Converters must map this to native glTF Node sharing (multiple nodes referencing a single mesh index). * **Point instancing (`UsdGeomPointInstancer`):** Used for massive arrays of atomic meshes (e.g., LED grids, warehouse clutter). It scatters a prototype using flat arrays of transforms. Converters must map this directly to the glTF EXT_mesh_gpu_instancing extension. @@ -272,14 +271,14 @@ While OpenUSD natively handles structural variants, many of the simulation tools * **Advanced compliance (material variants support):** Capable exporters may preserve material variations via the `KHR_materials_variants` extension. Because OpenUSD can arbitrarily override granular shader parameters, tools must evaluate each variant state, bake them into distinct glTF Material IDs in memory, and author the swap mapping. * **Fallback:** The glTF extension is invalid if a variant alters underlying mesh topology. If geometry changes, or if the exporter lacks discrete state-evaluation logic, tools must safely fall back to Baseline Compliance. -### 3.8 Conversion and Round-Tripping +### 3.8 Lossy Conversion OpenUSD and robotics XML formats (URDF, SDF, MJCF) are fundamentally mismatched paradigms. Because OpenUSD lacks native schemas for domain-specific data (e.g., URDF ``, MJCF ``), conversions are inherently lossy. Exporters must adhere to the following: * **Payload Resolution:** The active simulation payload (kinematics, inertia, colliders) is the extraction priority. OpenUSD composition arcs and instance proxies must be fully baked into explicit geometry and transforms, never discarded. * **API Translation:** Ros2*API schemas must map exclusively to modern extension blocks (e.g., SDF ``, MJCF ``). Obsolete approaches such as injecting legacy `` 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. -## Tools & Reference Implementations +## Compliance Checker A REP XXXX compliance checker is to be developed and shared with the community. The tool will provide validation of all REP recommendations for OpenUSD assets and supply actionable feedback for the user for every violation or non-conformance. ## References From 943244dd7cbd9d4c091b679485841e60097a83b0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Mon, 23 Mar 2026 19:07:20 +0100 Subject: [PATCH 035/111] Deformable bodies in layer Added 1.3 bullet point to handle deformable bodies and fallback Signed-off-by: Adam Dabrowski --- rep.md | 1 + 1 file changed, 1 insertion(+) diff --git a/rep.md b/rep.md index 02d518b..8c4941e 100644 --- a/rep.md +++ b/rep.md @@ -123,6 +123,7 @@ OpenUSD's native instancing mechanisms are designed for repetitive visual and st * *Kinematic Bodies:* Moving bodies that are animated but not dynamically driven by physics should set the physics:kinematicEnabled attribute to true. * *Dummy Frames:* Non-physical dummy frames (e.g., `camera_optical_frame`) must not possess a `PhysicsRigidBodyAPI`. They should be tracked using the `Ros2FrameAPI` as defined in Section 2.8. * **Inertia Representation:** Unlike URDF and SDFormat's 6-value symmetric matrix, OpenUSD requires an eigendecomposed inertia tensor. Converters must mathematically decompose the source matrix into physics:diagonalInertia (eigenvalues) and physics:principalAxes (quaternion). This native decomposed form is the strict single source of truth; custom 6-value array attributes must not be authored or parsed. +* **Deformable Bodies:** A vendor-neutral schema for deformable bodies is not yet ratified. Assets must isolate deformable soft-body physics into feature layer for specific domain or vendor (see Section 1.2.1). The asset's default variant must provide a rigid-body fallback approximation for interoperability. #### 1.3.1 Collisions Collision geometries should explicitly specify `purpose="guide"` and `physics:approximation="none"`. To ensure assets function across both standard physics engines and advanced contact-rich solvers (e.g., Newton), assets should employ a "Dual-Fidelity Pattern" utilizing a `collision_fidelity` OpenUSD `VariantSet`: From 6ff10161d27ebfd273e5b39bc3b105ce50a93674 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Mon, 23 Mar 2026 19:08:08 +0100 Subject: [PATCH 036/111] Update rep.md Fixed header Signed-off-by: Adam Dabrowski --- rep.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rep.md b/rep.md index 8c4941e..2b9893e 100644 --- a/rep.md +++ b/rep.md @@ -143,7 +143,7 @@ Collision meshes are not subject to visual LOD; their fidelity is governed by th #### 1.3.3 Contact Physics To ensure deterministic contact dynamics across engines, authors must bind a `UsdShadeMaterial` bearing the `UsdPhysicsMaterialAPI` to collision geometries. This material must define `physics:staticFriction`, `physics:dynamicFriction`, and `physics:restitution`. To prevent conflicts with visual shading networks, the physical material must be bound to the collision geometry explicitly using the physics material purpose (`material:binding:physics`), rather than the default all-purpose binding. Because engines utilize distinct friction models, converters must approximate these baseline values into their specific representations (e.g., SDF `` or MJCF ``). -### 1.3.4 Kinematic Loop Closures (`RoboticsLoopClosureAPI`) +#### 1.3.4 Kinematic Loop Closures (`RoboticsLoopClosureAPI`) OpenUSD `UsdPhysics` currently lacks a vendor-neutral (e.g., not `PhysxSchema` or `MjcPhysics`) mechanism to identify joints that close a kinematic loop. Because many robotics simulators use reduced-coordinate (e.g., Featherstone) solvers that require strict spanning trees, parsers must know which joint to exclude from the primary tree. * **Schema Application:** Asset authors must apply the `RoboticsLoopClosureAPI` to any `UsdPhysicsJoint` that closes a kinematic loop. * **Parser Responsibility:** Parsers traversing the `body0`/`body1` relationships to build the kinematic tree must prune their traversal when encountering this schema, handling the joint as a standalone constraint rather than a parent-child hierarchical link. From c6a5c7e82f844334911c9505d44b9551dcbe4701 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Tue, 24 Mar 2026 12:08:33 +0100 Subject: [PATCH 037/111] Update rep.md Updated to match 26.03 release of OpenUSD - While OpenUSD now supports WebAssembly, this does not change the need for editable format (glTF) export pathway. The language of the REP was shifted from web viewing to lightweight tools. - Radiance fields are now supported - they are given as a separate example of LOD variants in this REP Signed-off-by: Adam Dabrowski --- rep.md | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/rep.md b/rep.md index 2b9893e..4e8771b 100644 --- a/rep.md +++ b/rep.md @@ -133,10 +133,11 @@ Collision geometries should explicitly specify `purpose="guide"` and `physics:ap #### 1.3.2 Level of Detail Each link's visual and collision scopes should be organized as sibling children (e.g., `/{link}/visual`, `/{link}/collision`). -To ensure assets function across high-end renderers (Isaac Sim, O3DE), CPU-bound physics simulators (Gazebo, MuJoCo), and lightweight web viewers, assets should provide multiple geometric representations via a `visual_lod` VariantSet on the visual scope: +To ensure assets function across high-end renderers (Isaac Sim, O3DE), CPU-bound physics simulators (Gazebo, MuJoCo), and lightweight tooling, assets should provide multiple geometric representations via a `visual_lod` VariantSet on the visual scope: 1. **Medium (Default Variant):** Decimated geometry for real-time engines and standard simulation workloads. 2. **High (Optional Variant):** Full-fidelity source geometry (e.g. CAD). Suitable for ray-traced rendering and high-end visualization. -3. **Low (Optional Variant):** Aggressively simplified for web viewers, large-scale batch simulation, and GPU-instanced scenes (e.g., Genesis). +3. **Low (Optional Variant):** Simplified for lightweight tools, large-scale batch simulation, and GPU-instanced scenes (e.g., Genesis). +4. **Volumetric (Optional Variant):** Advanced radiance fields, such as 3D Gaussian Splats (`UsdVolParticleField`). Collision meshes are not subject to visual LOD; their fidelity is governed by the `collision_fidelity` VariantSet (Section 1.3.1). @@ -230,7 +231,7 @@ OpenUSD cameras natively face the -Z axis, whereas ROS 2 optical frames (REP 103 ## 3. Export and Conversion -OpenUSD is a vast standard supporting complex features. To guarantee that assets can be distributed, viewed in desktop tools (e.g., `usdview`) or lightweight web tools (e.g., Foxglove, Webviz, Rerun), and successfully converted to glTF 2.0, assets must adhere to this constrained subset. +OpenUSD is a vast standard supporting complex features. To guarantee that assets can be converted to glTF 2.0 and successfully exported to lightweight applications, assets must adhere to this constrained subset. ### 3.1 Material Portability * **Normative Surface:** Assets must use UsdPreviewSurface as the normative surface definition to ensure a direct mapping to glTF 2.0's pbrMetallicRoughness workflow. Target converters may also support OpenPBR[AOUSD-OPENPBR]. @@ -243,7 +244,7 @@ To ensure native portability across OpenUSD, lightweight simulators, and glTF 2. * **Data Maps:** Normal, Metallic, Roughness, and packed ORM maps must use lossless PNG. JPEG compression artifacts destructively alter PBR math. * **Color Maps:** BaseColor and Emissive maps may use JPEG to reduce footprint, provided they lack an alpha channel. * **KTX2** — Treat KTX2 strictly as a downstream glTF export target via `KHR_texture_basisu` glTF extension. Standard OpenUSD lacks native plugins for KTX2. -* **Prohibited formats:** EXR, TIFF, and other HDR/DCC formats must not be used for albedo, normal, or ORM maps in distributed assets. These formats have no glTF pathway and are unsupported by most web viewers. +* **Prohibited formats:** EXR, TIFF, and other HDR/DCC formats must not be used for albedo, normal, or ORM maps in distributed assets. These formats have no glTF pathway and introduce unacceptable payload overhead for lightweight tooling. * **Environment**: As an exception, High Dynamic Range (.hdr) files are permitted only for UsdLuxDomeLight environment maps. ### 3.3 Texture Baking From 093537fd291dc04d28ae99720fd301d795311d46 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Tue, 24 Mar 2026 14:19:41 +0100 Subject: [PATCH 038/111] reword visual_lod MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * introduction of new modality makes this a stretch Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- rep.md | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/rep.md b/rep.md index 4e8771b..6838d4b 100644 --- a/rep.md +++ b/rep.md @@ -130,16 +130,16 @@ Collision geometries should explicitly specify `purpose="guide"` and `physics:ap 1. **Baseline Approximation (Default Variant):** The default variant must contain "convexHull" or primitive shapes. 2. **Advanced Approximation (Optional Variant):** A secondary variant may contain high-fidelity concave trimeshes intended for Signed Distance Field (SDF) or Hydroelastic collision generation, provided the target simulator supports these paradigms. -#### 1.3.2 Level of Detail +#### 1.3.2 Visual Representation Each link's visual and collision scopes should be organized as sibling children (e.g., `/{link}/visual`, `/{link}/collision`). -To ensure assets function across high-end renderers (Isaac Sim, O3DE), CPU-bound physics simulators (Gazebo, MuJoCo), and lightweight tooling, assets should provide multiple geometric representations via a `visual_lod` VariantSet on the visual scope: -1. **Medium (Default Variant):** Decimated geometry for real-time engines and standard simulation workloads. -2. **High (Optional Variant):** Full-fidelity source geometry (e.g. CAD). Suitable for ray-traced rendering and high-end visualization. -3. **Low (Optional Variant):** Simplified for lightweight tools, large-scale batch simulation, and GPU-instanced scenes (e.g., Genesis). -4. **Volumetric (Optional Variant):** Advanced radiance fields, such as 3D Gaussian Splats (`UsdVolParticleField`). +To ensure assets function across high-end renderers (Isaac Sim, O3DE), CPU-bound physics simulators (Gazebo, MuJoCo), and lightweight tooling, assets should provide multiple visual representations via a `visual_representation` VariantSet on the visual scope. This VariantSet covers both mesh fidelity tiers and alternative representation modalities. +1. **`mesh_medium` (Default Variant):** Decimated mesh geometry for real-time engines and standard simulation workloads. +2. **`mesh_high` (Optional Variant):** Full-fidelity source mesh geometry (e.g. CAD). Suitable for ray-traced rendering and high-end visualization. +3. **`mesh_low` (Optional Variant):** Simplified mesh for lightweight tools, large-scale batch simulation, and GPU-instanced scenes (e.g., Genesis). +4. **`splat_gaussian` (Optional Variant):** 3D Gaussian Splat radiance field authored using the `UsdVolParticleField3DGaussianSplat` schema (OpenUSD 26.03). Particle-based radiance field representation rendered via splatting. -Collision meshes are not subject to visual LOD; their fidelity is governed by the `collision_fidelity` VariantSet (Section 1.3.1). +Collision meshes are not subject to this VariantSet; their fidelity is governed by the `collision_fidelity` VariantSet (Section 1.3.1). #### 1.3.3 Contact Physics To ensure deterministic contact dynamics across engines, authors must bind a `UsdShadeMaterial` bearing the `UsdPhysicsMaterialAPI` to collision geometries. This material must define `physics:staticFriction`, `physics:dynamicFriction`, and `physics:restitution`. To prevent conflicts with visual shading networks, the physical material must be bound to the collision geometry explicitly using the physics material purpose (`material:binding:physics`), rather than the default all-purpose binding. Because engines utilize distinct friction models, converters must approximate these baseline values into their specific representations (e.g., SDF `` or MJCF ``). From fedd6d2ae962decbf0331c0f45bfb743da601f80 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Tue, 24 Mar 2026 14:42:41 +0100 Subject: [PATCH 039/111] Apply suggestion from @adamdbrw Signed-off-by: Adam Dabrowski --- rep.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rep.md b/rep.md index 6838d4b..b2f34e5 100644 --- a/rep.md +++ b/rep.md @@ -137,7 +137,7 @@ To ensure assets function across high-end renderers (Isaac Sim, O3DE), CPU-bound 1. **`mesh_medium` (Default Variant):** Decimated mesh geometry for real-time engines and standard simulation workloads. 2. **`mesh_high` (Optional Variant):** Full-fidelity source mesh geometry (e.g. CAD). Suitable for ray-traced rendering and high-end visualization. 3. **`mesh_low` (Optional Variant):** Simplified mesh for lightweight tools, large-scale batch simulation, and GPU-instanced scenes (e.g., Genesis). -4. **`splat_gaussian` (Optional Variant):** 3D Gaussian Splat radiance field authored using the `UsdVolParticleField3DGaussianSplat` schema (OpenUSD 26.03). Particle-based radiance field representation rendered via splatting. +4. **`volumetric_splat` (Optional Variant):** 3D Gaussian Splat radiance field authored using the `UsdVolParticleField3DGaussianSplat` schema (OpenUSD 26.03). Collision meshes are not subject to this VariantSet; their fidelity is governed by the `collision_fidelity` VariantSet (Section 1.3.1). From 590d0161230e98b09d9f4135adfad977be5d03e1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Wed, 25 Mar 2026 10:40:11 +0100 Subject: [PATCH 040/111] use excludeFromArticulation instaed of new schema MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- rep.md | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/rep.md b/rep.md index b2f34e5..1ba1210 100644 --- a/rep.md +++ b/rep.md @@ -116,7 +116,7 @@ OpenUSD's native instancing mechanisms are designed for repetitive visual and st * **Articulation Roots:** A composed simulation stage must contain at most one `UsdPhysicsArticulationRootAPI` per connected kinematic tree. * Assets (e.g., a modular gripper) should be self-contained with an articulation root for standalone use. * When composed into a larger kinematic tree, the composing stage should use the OpenUSD list-edit operation `delete apiSchemas = ["PhysicsArticulationRootAPI"]` to prune nested articulation roots. This prevents reduced-coordinate physics solvers from fracturing the robot. -* **Loop Closures:** Articulations must form a spanning tree. Joints introducing loop-closing constraints (e.g., parallel linkages) must use the newly introduced `RoboticsLoopClosureAPI` marker schema. +* **Loop Closures:** Articulations must form a spanning tree. Joints introducing loop-closing constraints (e.g., parallel linkages) must set `physics:excludeFromArticulation = true` (see Section 1.3.4). * **Mass Properties:** Assets and simulators must follow `UsdPhysicsMassAPI` guidelines. Dynamic bodies must define a strictly positive mass (mass > 0). Setting mass = 0 to imply infinite/static mass violates the UsdPhysics specification, which ignores 0.0 and falls back to a computed default mass. Instead, authors must use standard mechanisms for non-dynamic bodies: * Static Environments: Fixed props (e.g., walls, racks) must possess a PhysicsCollisionAPI but omit the PhysicsRigidBodyAPI. OpenUSD implicitly treats these as having zero velocity and infinite mass. * Robot Anchors: A fixed robot base must have a valid mass > 0 and be anchored via a UsdPhysicsFixedJoint with an empty physics:body0 relationship (which natively represents the world). @@ -144,10 +144,10 @@ Collision meshes are not subject to this VariantSet; their fidelity is governed #### 1.3.3 Contact Physics To ensure deterministic contact dynamics across engines, authors must bind a `UsdShadeMaterial` bearing the `UsdPhysicsMaterialAPI` to collision geometries. This material must define `physics:staticFriction`, `physics:dynamicFriction`, and `physics:restitution`. To prevent conflicts with visual shading networks, the physical material must be bound to the collision geometry explicitly using the physics material purpose (`material:binding:physics`), rather than the default all-purpose binding. Because engines utilize distinct friction models, converters must approximate these baseline values into their specific representations (e.g., SDF `` or MJCF ``). -#### 1.3.4 Kinematic Loop Closures (`RoboticsLoopClosureAPI`) -OpenUSD `UsdPhysics` currently lacks a vendor-neutral (e.g., not `PhysxSchema` or `MjcPhysics`) mechanism to identify joints that close a kinematic loop. Because many robotics simulators use reduced-coordinate (e.g., Featherstone) solvers that require strict spanning trees, parsers must know which joint to exclude from the primary tree. -* **Schema Application:** Asset authors must apply the `RoboticsLoopClosureAPI` to any `UsdPhysicsJoint` that closes a kinematic loop. -* **Parser Responsibility:** Parsers traversing the `body0`/`body1` relationships to build the kinematic tree must prune their traversal when encountering this schema, handling the joint as a standalone constraint rather than a parent-child hierarchical link. +#### 1.3.4 Kinematic Loop Closures (`physics:excludeFromArticulation`) +OpenUSD `UsdPhysics` provides a vendor-neutral mechanism to identify joints that should be excluded from reduced-coordinate articulations: the `physics:excludeFromArticulation` attribute on `UsdPhysicsJoint`. Because many robotics simulators use reduced-coordinate (e.g., Featherstone) solvers that require strict spanning trees, parsers must know which joint to exclude from the primary tree. +* **Attribute Usage:** Asset authors must set `physics:excludeFromArticulation = true` on any `UsdPhysicsJoint` that closes a kinematic loop. +* **Parser Responsibility:** Parsers traversing the `body0`/`body1` relationships to build the kinematic tree must prune their traversal when encountering this flag, handling the joint as a standalone constraint rather than a parent-child hierarchical link. ### 1.4 Isolation of vendor-specific extensions From 54d3b6ab1c85971863e91cfc41a1b86602f1a1f7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Wed, 25 Mar 2026 12:50:23 +0100 Subject: [PATCH 041/111] shorten, remove redundant section MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- rep.md | 8 +------- 1 file changed, 1 insertion(+), 7 deletions(-) diff --git a/rep.md b/rep.md index 1ba1210..0b90d23 100644 --- a/rep.md +++ b/rep.md @@ -116,7 +116,7 @@ OpenUSD's native instancing mechanisms are designed for repetitive visual and st * **Articulation Roots:** A composed simulation stage must contain at most one `UsdPhysicsArticulationRootAPI` per connected kinematic tree. * Assets (e.g., a modular gripper) should be self-contained with an articulation root for standalone use. * When composed into a larger kinematic tree, the composing stage should use the OpenUSD list-edit operation `delete apiSchemas = ["PhysicsArticulationRootAPI"]` to prune nested articulation roots. This prevents reduced-coordinate physics solvers from fracturing the robot. -* **Loop Closures:** Articulations must form a spanning tree. Joints introducing loop-closing constraints (e.g., parallel linkages) must set `physics:excludeFromArticulation = true` (see Section 1.3.4). +* **Loop Closures:** Articulations must form a spanning tree. Joints that close a kinematic loop (e.g., parallel linkages, four-bar mechanisms) must set `physics:excludeFromArticulation = true`. Parsers building the kinematic tree must treat these joints as standalone maximal-coordinate constraints rather than parent-child links. * **Mass Properties:** Assets and simulators must follow `UsdPhysicsMassAPI` guidelines. Dynamic bodies must define a strictly positive mass (mass > 0). Setting mass = 0 to imply infinite/static mass violates the UsdPhysics specification, which ignores 0.0 and falls back to a computed default mass. Instead, authors must use standard mechanisms for non-dynamic bodies: * Static Environments: Fixed props (e.g., walls, racks) must possess a PhysicsCollisionAPI but omit the PhysicsRigidBodyAPI. OpenUSD implicitly treats these as having zero velocity and infinite mass. * Robot Anchors: A fixed robot base must have a valid mass > 0 and be anchored via a UsdPhysicsFixedJoint with an empty physics:body0 relationship (which natively represents the world). @@ -144,12 +144,6 @@ Collision meshes are not subject to this VariantSet; their fidelity is governed #### 1.3.3 Contact Physics To ensure deterministic contact dynamics across engines, authors must bind a `UsdShadeMaterial` bearing the `UsdPhysicsMaterialAPI` to collision geometries. This material must define `physics:staticFriction`, `physics:dynamicFriction`, and `physics:restitution`. To prevent conflicts with visual shading networks, the physical material must be bound to the collision geometry explicitly using the physics material purpose (`material:binding:physics`), rather than the default all-purpose binding. Because engines utilize distinct friction models, converters must approximate these baseline values into their specific representations (e.g., SDF `` or MJCF ``). -#### 1.3.4 Kinematic Loop Closures (`physics:excludeFromArticulation`) -OpenUSD `UsdPhysics` provides a vendor-neutral mechanism to identify joints that should be excluded from reduced-coordinate articulations: the `physics:excludeFromArticulation` attribute on `UsdPhysicsJoint`. Because many robotics simulators use reduced-coordinate (e.g., Featherstone) solvers that require strict spanning trees, parsers must know which joint to exclude from the primary tree. -* **Attribute Usage:** Asset authors must set `physics:excludeFromArticulation = true` on any `UsdPhysicsJoint` that closes a kinematic loop. -* **Parser Responsibility:** Parsers traversing the `body0`/`body1` relationships to build the kinematic tree must prune their traversal when encountering this flag, handling the joint as a standalone constraint rather than a parent-child hierarchical link. - - ### 1.4 Isolation of vendor-specific extensions Engine-specific parameters (e.g., solver iterations, GPU tensors) not covered by core OpenUSD schemas must be explicitly namespaced with a vendor prefix (e.g., mujoco:, isaac:). This applies to both formal vendor-supplied API schemas and ad-hoc custom attributes. This proprietary metadata must be strictly isolated within the ETL Pipeline's "Proprietary Layer" (Section 1.2.1) and never authored in the baseline simulation payload. Authors must strive to minimize proprietary layer to strictly necessary. From e7b191461e4193026d431cc04e5eafc7d1fefe2c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Fri, 27 Mar 2026 10:49:40 +0100 Subject: [PATCH 042/111] add schema.usda for Ros2*Apis MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * add scaffolding for CodeGen and building instructions * prepare discovery validation tool Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- schema/BUILDING.md | 55 ++++ schema/env.sh | 13 + schema/plugin/usdRos2/.gitignore | 6 + schema/plugin/usdRos2/__init__.py | 3 + schema/plugin/usdRos2/module.cpp | 12 + schema/plugin/usdRos2/resources/.gitignore | 3 + schema/schema.usda | 344 +++++++++++++++++++++ schema/tools/traverse_ros2.py | 87 ++++++ 8 files changed, 523 insertions(+) create mode 100644 schema/BUILDING.md create mode 100644 schema/env.sh create mode 100644 schema/plugin/usdRos2/.gitignore create mode 100644 schema/plugin/usdRos2/__init__.py create mode 100644 schema/plugin/usdRos2/module.cpp create mode 100644 schema/plugin/usdRos2/resources/.gitignore create mode 100644 schema/schema.usda create mode 100644 schema/tools/traverse_ros2.py diff --git a/schema/BUILDING.md b/schema/BUILDING.md new file mode 100644 index 0000000..b86a0c8 --- /dev/null +++ b/schema/BUILDING.md @@ -0,0 +1,55 @@ +# Building the usdRos2 Schema Plugin + +All commands run from `schema/`. + +## Prerequisites + +- OpenUSD v26.03+ built with Python support +- Set environment: + ```bash + source env.sh + ``` + +## Codeless Plugin (schema awareness only, no C++ build) + +Add `bool skipCodeGeneration = true` to `schema.usda` GLOBAL customData, then: + +```bash +mkdir -p plugin/usdRos2/resources +usdGenSchema schema.usda plugin/usdRos2/resources +``` + +Fix paths in `plugin/usdRos2/resources/plugInfo.json`: +```json +"LibraryPath": "", +"ResourcePath": ".", +"Root": ".", +"Type": "resource" +``` + +Register: +```bash +export PXR_PLUGINPATH_NAME=$(pwd)/plugin/usdRos2/resources +``` + +## Full C++ + Python Code Generation + +Remove `skipCodeGeneration` from `schema.usda` if present, then: + +```bash +usdGenSchema schema.usda plugin/usdRos2 +``` + +This generates per schema: `{name}.h`, `{name}.cpp`, `wrap{Name}.cpp`, +plus shared `tokens.h/.cpp`, `plugInfo.json`, `generatedSchema.usda`. + +Only changed files are rewritten on subsequent runs. + +## Validation + +```bash +usdchecker ../examples/otto600/OTTO600.usda +``` +```bash +PXR_PLUGINPATH_NAME=$(pwd)/plugin/usdRos2/resources python3 tools/traverse_ros2.py +``` diff --git a/schema/env.sh b/schema/env.sh new file mode 100644 index 0000000..2bfecbc --- /dev/null +++ b/schema/env.sh @@ -0,0 +1,13 @@ +#!/bin/bash +# Environment setup for OpenUSD v26.03+ tooling +# Set USD_INSTALL before sourcing, e.g.: +# export USD_INSTALL=/path/to/openusd/install && source env.sh + +if [ -z "${USD_INSTALL}" ]; then + echo "ERROR: USD_INSTALL is not set. Point it to your OpenUSD install directory." >&2 + return 1 2>/dev/null || exit 1 +fi + +export PATH=${USD_INSTALL}/bin:${PATH} +export PYTHONPATH=${USD_INSTALL}/lib/python:${PYTHONPATH} +export LD_LIBRARY_PATH=${USD_INSTALL}/lib:${LD_LIBRARY_PATH} diff --git a/schema/plugin/usdRos2/.gitignore b/schema/plugin/usdRos2/.gitignore new file mode 100644 index 0000000..6a3e985 --- /dev/null +++ b/schema/plugin/usdRos2/.gitignore @@ -0,0 +1,6 @@ +# Generated by usdGenSchema - regenerate via: usdGenSchema schema.usda plugin/usdRos2 +*.h +*.cpp +!module.cpp +generatedSchema.* +plugInfo.json diff --git a/schema/plugin/usdRos2/__init__.py b/schema/plugin/usdRos2/__init__.py new file mode 100644 index 0000000..83b5b6a --- /dev/null +++ b/schema/plugin/usdRos2/__init__.py @@ -0,0 +1,3 @@ +from pxr import Plug + +Plug.Registry().GetAllPlugins() diff --git a/schema/plugin/usdRos2/module.cpp b/schema/plugin/usdRos2/module.cpp new file mode 100644 index 0000000..422c3ed --- /dev/null +++ b/schema/plugin/usdRos2/module.cpp @@ -0,0 +1,12 @@ +// Copyright (c) 2026 Robotec.ai +// SPDX-License-Identifier: Apache-2.0 + +#include "pxr/pxr.h" +#include "pxr/base/tf/pyModule.h" + +PXR_NAMESPACE_USING_DIRECTIVE + +TF_WRAP_MODULE +{ +#include "generatedSchema.module.h" +} diff --git a/schema/plugin/usdRos2/resources/.gitignore b/schema/plugin/usdRos2/resources/.gitignore new file mode 100644 index 0000000..5652327 --- /dev/null +++ b/schema/plugin/usdRos2/resources/.gitignore @@ -0,0 +1,3 @@ +# Generated by usdGenSchema (codeless plugin) +generatedSchema.usda +plugInfo.json diff --git a/schema/schema.usda b/schema/schema.usda new file mode 100644 index 0000000..d80cd64 --- /dev/null +++ b/schema/schema.usda @@ -0,0 +1,344 @@ +#usda 1.0 +( + "ROS 2 Integration Schemas for OpenUSD Simulation Asset Interoperability." + " Defines declarative, engine-agnostic API schemas for ROS 2 interfaces" + " as specified in REP-2040, Section 2." + subLayers = [ + @usd/schema.usda@ + ] +) + +over "GLOBAL" ( + customData = { + string libraryName = "usdRos2" + string libraryPath = "usdRos2" + string libraryPrefix = "UsdRos2" + dictionary libraryTokens = { + # --- Role tokens (shared by Topic, Service, Action) --- + dictionary publisher = { + string doc = """Role token indicating the interface is a publisher.""" + } + dictionary subscription = { + string doc = """Role token indicating the interface is a subscription.""" + } + dictionary server = { + string doc = """Role token indicating the interface is a server.""" + } + dictionary client = { + string doc = """Role token indicating the interface is a client.""" + } + + # --- QoS tokens --- + dictionary system_default = { + string doc = """QoS policy value deferring to the ROS 2 system default.""" + } + dictionary reliable = { + string doc = """QoS reliability policy requesting reliable delivery.""" + } + dictionary best_effort = { + string doc = """QoS reliability policy requesting best-effort delivery.""" + } + dictionary transient_local = { + string doc = """QoS durability policy requesting transient-local + storage of messages for late-joining subscriptions.""" + } + dictionary volatile_ = { + string value = "volatile" + string doc = """QoS durability policy requesting volatile (no persistence).""" + } + dictionary keep_last = { + string doc = """QoS history policy keeping only the last N messages.""" + } + dictionary keep_all = { + string doc = """QoS history policy keeping all messages.""" + } + + # --- Frame tokens --- + dictionary world = { + string doc = """Default parent frame for the top-most Ros2ContextAPI.""" + } + } + } +) +{ +} + +# ====================================================================== +# Section 2.1 - Ros2ContextAPI +# ====================================================================== + +class "Ros2ContextAPI" ( + inherits = + customData = { + token apiSchemaType = "singleApply" + string className = "ContextAPI" + } + doc = """Defines the ROS 2 context for a simulation asset. + + The root prim of a ROS-interfaced simulation asset may apply this + schema to define its namespace and optionally override the DDS + domain ID. The namespace is additive in the asset hierarchy and + with a top-level namespace set during simulation deployment + (e.g. via the SpawnEntity service). + """ +) +{ + uniform string ros2:context:namespace ( + customData = { + string apiName = "namespace" + } + doc = """Prefixes all topics within this scope (e.g. '/robot_1'). + The namespace is additive in the asset hierarchy.""" + ) + + uniform int ros2:context:domain_id ( + customData = { + string apiName = "domainId" + } + doc = """Overrides the default ROS Domain ID for interfaces + descending from this context.""" + ) + + uniform string ros2:context:parent_frame = "world" ( + customData = { + string apiName = "parentFrame" + } + doc = """Defines the parent frame_id used when the simulator + broadcasts the ground-truth transform of this context's root + prim. Only valid for the top-most context in the resolved USD + Stage and ignored otherwise.""" + ) +} + +# ====================================================================== +# Section 2.4 - Ros2TopicAPI +# ====================================================================== + +class "Ros2TopicAPI" ( + inherits = + customData = { + token apiSchemaType = "singleApply" + string className = "TopicAPI" + } + doc = """Applied to prims exchanging streaming ROS 2 data. + + Simulators spawn the corresponding publisher or subscription at + runtime. Robot-wide interfaces go on or beneath the Ros2ContextAPI + prim; sensor interfaces go on a child Xform of the physical link, + one interface per prim. Interface prims must reside outside payloads + and do not generate TF frames. + """ +) +{ + # ------------------------------------------------------------------ + # Core Attributes (Required) + # ------------------------------------------------------------------ + + uniform token ros2:topic:role ( + customData = { + string apiName = "role" + } + allowedTokens = ["publisher", "subscription"] + doc = """Defines whether this interface acts as a publisher or a + subscription.""" + ) + + uniform string ros2:topic:name ( + customData = { + string apiName = "name" + } + doc = """The topic name, relative to the active ROS 2 namespace + inherited from the nearest ancestor Ros2ContextAPI. Must adhere + to ROS 2 topic naming rules (alphanumeric, underscores, and + forward slashes only; cannot start with a number).""" + ) + + uniform string ros2:topic:type ( + customData = { + string apiName = "type" + } + doc = """The ROS 2 message type string (e.g. 'sensor_msgs/msg/Image'). + Simulators must attempt to resolve this type dynamically against the + sourced ROS 2 environment. If the type is not found, the simulator + must safely disable this interface and emit a warning.""" + ) + + uniform double ros2:topic:publish_rate ( + customData = { + string apiName = "publishRate" + } + doc = """Target publication frequency in Hz. Required for publishers; + ignored for subscriptions.""" + ) + + # ------------------------------------------------------------------ + # Quality of Service (QoS) Attributes + # ------------------------------------------------------------------ + + uniform bool ros2:topic:qos:match_publisher = false ( + customData = { + string apiName = "qosMatchPublisher" + } + doc = """For subscriptions only. If true, the simulator bridge must + attempt to use ROS 2 QoS matching to adapt to the discovered + publisher, ignoring explicit reliability and durability settings.""" + ) + + uniform token ros2:topic:qos:reliability = "system_default" ( + customData = { + string apiName = "qosReliability" + } + allowedTokens = ["system_default", "reliable", "best_effort"] + doc = """Maps to rmw_qos_profile_t reliability policy. As per + REP 2003, simulated sensors should default to 'system_default' + which maps to best-effort.""" + ) + + uniform token ros2:topic:qos:durability = "system_default" ( + customData = { + string apiName = "qosDurability" + } + allowedTokens = ["system_default", "transient_local", "volatile"] + doc = """Maps to rmw_qos_profile_t durability policy. Map + publishers should use 'transient_local'.""" + ) + + uniform token ros2:topic:qos:history = "system_default" ( + customData = { + string apiName = "qosHistory" + } + allowedTokens = ["system_default", "keep_last", "keep_all"] + doc = """Maps to rmw_qos_profile_t history policy.""" + ) + + uniform int ros2:topic:qos:depth = 10 ( + customData = { + string apiName = "qosDepth" + } + doc = """Queue size. Evaluated only when history is 'keep_last'.""" + ) +} + +# ====================================================================== +# Section 2.5 - Ros2ServiceAPI +# ====================================================================== + +class "Ros2ServiceAPI" ( + inherits = + customData = { + token apiSchemaType = "singleApply" + string className = "ServiceAPI" + } + doc = """Applied to prims handling synchronous ROS 2 requests. + + Simulators spawn the corresponding server or client at runtime. + Same placement, resolution, and TF exclusion rules as Ros2TopicAPI. + """ +) +{ + uniform token ros2:service:role ( + customData = { + string apiName = "role" + } + allowedTokens = ["server", "client"] + doc = """Defines whether this interface acts as a server or a + client. Simulation assets are typically servers.""" + ) + + uniform string ros2:service:name ( + customData = { + string apiName = "name" + } + doc = """The service name, relative to the active ROS 2 namespace. + Must adhere to ROS 2 naming rules.""" + ) + + uniform string ros2:service:type ( + customData = { + string apiName = "type" + } + doc = """The ROS 2 service type (e.g. 'std_srvs/srv/SetBool'). + Simulators must resolve dynamically; disable on failure.""" + ) +} + +# ====================================================================== +# Section 2.6 - Ros2ActionAPI +# ====================================================================== + +class "Ros2ActionAPI" ( + inherits = + customData = { + token apiSchemaType = "singleApply" + string className = "ActionAPI" + } + doc = """Applied to prims handling asynchronous, long-running ROS 2 behaviors. + + Simulators spawn the corresponding server or client at runtime. + Same placement, resolution, and TF exclusion rules as Ros2TopicAPI. + """ +) +{ + uniform token ros2:action:role ( + customData = { + string apiName = "role" + } + allowedTokens = ["server", "client"] + doc = """Defines whether this interface acts as a server or a + client. Simulation assets are typically servers.""" + ) + + uniform string ros2:action:name ( + customData = { + string apiName = "name" + } + doc = """The action name, relative to the active ROS 2 namespace. + Must adhere to ROS 2 naming rules.""" + ) + + uniform string ros2:action:type ( + customData = { + string apiName = "type" + } + doc = """The ROS 2 action type + (e.g. 'control_msgs/action/FollowJointTrajectory'). + Simulators must resolve dynamically; disable on failure.""" + ) +} + +# ====================================================================== +# Section 2.7 - Ros2FrameAPI +# ====================================================================== + +class "Ros2FrameAPI" ( + inherits = + customData = { + token apiSchemaType = "singleApply" + string className = "FrameAPI" + } + doc = """Explicit TF frame broadcasting for non-physical dummy frames. + + Apply this schema to UsdGeomXform prims that need TF frames but do + not possess a PhysicsRigidBodyAPI (e.g. camera_optical_frame, + grasp_point). Physical links connected via joints get implicit TF + broadcasting and do not need this schema. + """ +) +{ + uniform string ros2:frame:id ( + customData = { + string apiName = "id" + } + doc = """Overrides the TF frame name. If omitted, the validated + Prim name is used as the frame_id.""" + ) + + uniform bool ros2:frame:static = true ( + customData = { + string apiName = "static" + } + doc = """Defines the broadcast destination. If true, the simulator + broadcasts to /tf_static. If false (e.g. an Xform animated by + USD TimeSamples), the simulator broadcasts to /tf.""" + ) +} diff --git a/schema/tools/traverse_ros2.py b/schema/tools/traverse_ros2.py new file mode 100644 index 0000000..4f93b1c --- /dev/null +++ b/schema/tools/traverse_ros2.py @@ -0,0 +1,87 @@ +# ABOUTME: Traverses a composed USD stage and discovers all ROS 2 interface +# ABOUTME: schemas (Ros2*API), printing a summary table of interfaces and attributes. + +import sys +from collections import defaultdict +from pxr import Usd, Sdf + + +def get_ros2_schemas(prim): + """Extract Ros2*API schema names from a prim's apiSchemas metadata. + + Works both with and without the codeless plugin loaded. + With plugin: GetAppliedSchemas() returns Ros2 schemas directly. + Without plugin: falls back to reading raw apiSchemas listOp metadata. + """ + # Try the proper API first (works when plugin is registered) + applied = prim.GetAppliedSchemas() + ros2 = [s for s in applied if s.startswith("Ros2")] + if ros2: + return ros2 + + # Fallback: read the raw apiSchemas metadata listOp and extract + # the composed explicit items (result of all prepend/append/delete ops) + meta = prim.GetMetadata("apiSchemas") + if meta is None: + return [] + items = list(meta.explicitItems) if meta.explicitItems else [] + return [s for s in items if s.startswith("Ros2")] + + +def get_ros2_attributes(prim): + """Read all ros2:* authored attributes from a prim.""" + attrs = {} + for attr in prim.GetAttributes(): + name = attr.GetName() + if name.startswith("ros2:"): + value = attr.Get() + authored = attr.IsAuthored() + attrs[name] = (value, authored) + return attrs + + +def traverse_ros2_interfaces(stage_path): + """Load a USD stage and print all ROS 2 interface schemas found.""" + stage = Usd.Stage.Open(stage_path) + if not stage: + print(f"ERROR: Could not open stage: {stage_path}") + return 1 + + print(f"=== ROS 2 Interface Summary for {stage_path} ===") + print(f"Stage up axis: {stage.GetMetadata('upAxis')}") + print(f"Stage meters/unit: {stage.GetMetadata('metersPerUnit')}") + print() + + # Collect prims grouped by schema type + schema_prims = defaultdict(list) + total = 0 + + for prim in Usd.PrimRange(stage.GetPseudoRoot()): + ros2_schemas = get_ros2_schemas(prim) + if not ros2_schemas: + continue + total += 1 + attrs = get_ros2_attributes(prim) + for schema in ros2_schemas: + schema_prims[schema].append((prim.GetPath(), attrs)) + + print(f"Found {total} prims with Ros2 API schemas\n") + + # Print grouped by schema type + for schema in sorted(schema_prims.keys()): + prims = schema_prims[schema] + print(f"--- {schema} ({len(prims)} prim{'s' if len(prims) != 1 else ''}) ---") + for path, attrs in prims: + print(f" {path}") + for attr_name in sorted(attrs.keys()): + value, authored = attrs[attr_name] + marker = "" if authored else " (fallback)" + print(f" {attr_name} = {value!r}{marker}") + print() + + return 0 + + +if __name__ == "__main__": + stage_path = sys.argv[1] if len(sys.argv) > 1 else "../examples/otto600/OTTO600.usda" + sys.exit(traverse_ros2_interfaces(stage_path)) From 1d468891f81cba1e351b3dd9d97f697d16c893d1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Fri, 27 Mar 2026 14:44:51 +0100 Subject: [PATCH 043/111] add Ros2*API schema definition and Tools section MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Add schema/schema.usda with normative OpenUSD schema definitions for Ros2ContextAPI, Ros2TopicAPI, Ros2ServiceAPI, Ros2ActionAPI, and Ros2FrameAPI. Compatible with usdGenSchema for codeless plugin or full C++/Python code generation. Add Tools section to rep.md referencing the schema definition and the planned compliance checker. Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- rep.md | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/rep.md b/rep.md index 0b90d23..325190e 100644 --- a/rep.md +++ b/rep.md @@ -274,8 +274,13 @@ OpenUSD and robotics XML formats (URDF, SDF, MJCF) are fundamentally mismatched * **API Translation:** Ros2*API schemas must map exclusively to modern extension blocks (e.g., SDF ``, MJCF ``). Obsolete approaches such as injecting legacy `` 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. -## Compliance Checker -A REP XXXX compliance checker is to be developed and shared with the community. The tool will provide validation of all REP recommendations for OpenUSD assets and supply actionable feedback for the user for every violation or non-conformance. +## Tools + +### Schema Definition +The normative OpenUSD schema definition for all `Ros2*API` schemas is provided in `schema/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. + +### Compliance Checker +A REP-2040 compliance checker is to be developed and shared with the community. The tool will provide validation of all REP recommendations for OpenUSD assets and supply actionable feedback for the user for every violation or non-conformance. ## References * **[NVIDIA-ETL-PIPELINE]** NVIDIA, Intrinsic, Disney Research. "Using OpenUSD for Modular and Scalable Robotic Simulation and Development". URL: `https://developer.nvidia.com/blog/using-openusd-for-modular-and-scalable-robotic-simulation-and-development/` From 2980379cc0e22818432a3573e85a86919f61a9fb Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Fri, 27 Mar 2026 14:47:05 +0100 Subject: [PATCH 044/111] move tooling out of REP PR, keep only schema.usda MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Remove scaffolding, build instructions, and traversal tools from the REP branch. These belong in the reference implementation, not the specification. Only schema/schema.usda and the Tools section in rep.md remain. Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- schema/BUILDING.md | 55 -------------- schema/env.sh | 13 ---- schema/plugin/usdRos2/.gitignore | 6 -- schema/plugin/usdRos2/__init__.py | 3 - schema/plugin/usdRos2/module.cpp | 12 --- schema/plugin/usdRos2/resources/.gitignore | 3 - schema/tools/traverse_ros2.py | 87 ---------------------- 7 files changed, 179 deletions(-) delete mode 100644 schema/BUILDING.md delete mode 100644 schema/env.sh delete mode 100644 schema/plugin/usdRos2/.gitignore delete mode 100644 schema/plugin/usdRos2/__init__.py delete mode 100644 schema/plugin/usdRos2/module.cpp delete mode 100644 schema/plugin/usdRos2/resources/.gitignore delete mode 100644 schema/tools/traverse_ros2.py diff --git a/schema/BUILDING.md b/schema/BUILDING.md deleted file mode 100644 index b86a0c8..0000000 --- a/schema/BUILDING.md +++ /dev/null @@ -1,55 +0,0 @@ -# Building the usdRos2 Schema Plugin - -All commands run from `schema/`. - -## Prerequisites - -- OpenUSD v26.03+ built with Python support -- Set environment: - ```bash - source env.sh - ``` - -## Codeless Plugin (schema awareness only, no C++ build) - -Add `bool skipCodeGeneration = true` to `schema.usda` GLOBAL customData, then: - -```bash -mkdir -p plugin/usdRos2/resources -usdGenSchema schema.usda plugin/usdRos2/resources -``` - -Fix paths in `plugin/usdRos2/resources/plugInfo.json`: -```json -"LibraryPath": "", -"ResourcePath": ".", -"Root": ".", -"Type": "resource" -``` - -Register: -```bash -export PXR_PLUGINPATH_NAME=$(pwd)/plugin/usdRos2/resources -``` - -## Full C++ + Python Code Generation - -Remove `skipCodeGeneration` from `schema.usda` if present, then: - -```bash -usdGenSchema schema.usda plugin/usdRos2 -``` - -This generates per schema: `{name}.h`, `{name}.cpp`, `wrap{Name}.cpp`, -plus shared `tokens.h/.cpp`, `plugInfo.json`, `generatedSchema.usda`. - -Only changed files are rewritten on subsequent runs. - -## Validation - -```bash -usdchecker ../examples/otto600/OTTO600.usda -``` -```bash -PXR_PLUGINPATH_NAME=$(pwd)/plugin/usdRos2/resources python3 tools/traverse_ros2.py -``` diff --git a/schema/env.sh b/schema/env.sh deleted file mode 100644 index 2bfecbc..0000000 --- a/schema/env.sh +++ /dev/null @@ -1,13 +0,0 @@ -#!/bin/bash -# Environment setup for OpenUSD v26.03+ tooling -# Set USD_INSTALL before sourcing, e.g.: -# export USD_INSTALL=/path/to/openusd/install && source env.sh - -if [ -z "${USD_INSTALL}" ]; then - echo "ERROR: USD_INSTALL is not set. Point it to your OpenUSD install directory." >&2 - return 1 2>/dev/null || exit 1 -fi - -export PATH=${USD_INSTALL}/bin:${PATH} -export PYTHONPATH=${USD_INSTALL}/lib/python:${PYTHONPATH} -export LD_LIBRARY_PATH=${USD_INSTALL}/lib:${LD_LIBRARY_PATH} diff --git a/schema/plugin/usdRos2/.gitignore b/schema/plugin/usdRos2/.gitignore deleted file mode 100644 index 6a3e985..0000000 --- a/schema/plugin/usdRos2/.gitignore +++ /dev/null @@ -1,6 +0,0 @@ -# Generated by usdGenSchema - regenerate via: usdGenSchema schema.usda plugin/usdRos2 -*.h -*.cpp -!module.cpp -generatedSchema.* -plugInfo.json diff --git a/schema/plugin/usdRos2/__init__.py b/schema/plugin/usdRos2/__init__.py deleted file mode 100644 index 83b5b6a..0000000 --- a/schema/plugin/usdRos2/__init__.py +++ /dev/null @@ -1,3 +0,0 @@ -from pxr import Plug - -Plug.Registry().GetAllPlugins() diff --git a/schema/plugin/usdRos2/module.cpp b/schema/plugin/usdRos2/module.cpp deleted file mode 100644 index 422c3ed..0000000 --- a/schema/plugin/usdRos2/module.cpp +++ /dev/null @@ -1,12 +0,0 @@ -// Copyright (c) 2026 Robotec.ai -// SPDX-License-Identifier: Apache-2.0 - -#include "pxr/pxr.h" -#include "pxr/base/tf/pyModule.h" - -PXR_NAMESPACE_USING_DIRECTIVE - -TF_WRAP_MODULE -{ -#include "generatedSchema.module.h" -} diff --git a/schema/plugin/usdRos2/resources/.gitignore b/schema/plugin/usdRos2/resources/.gitignore deleted file mode 100644 index 5652327..0000000 --- a/schema/plugin/usdRos2/resources/.gitignore +++ /dev/null @@ -1,3 +0,0 @@ -# Generated by usdGenSchema (codeless plugin) -generatedSchema.usda -plugInfo.json diff --git a/schema/tools/traverse_ros2.py b/schema/tools/traverse_ros2.py deleted file mode 100644 index 4f93b1c..0000000 --- a/schema/tools/traverse_ros2.py +++ /dev/null @@ -1,87 +0,0 @@ -# ABOUTME: Traverses a composed USD stage and discovers all ROS 2 interface -# ABOUTME: schemas (Ros2*API), printing a summary table of interfaces and attributes. - -import sys -from collections import defaultdict -from pxr import Usd, Sdf - - -def get_ros2_schemas(prim): - """Extract Ros2*API schema names from a prim's apiSchemas metadata. - - Works both with and without the codeless plugin loaded. - With plugin: GetAppliedSchemas() returns Ros2 schemas directly. - Without plugin: falls back to reading raw apiSchemas listOp metadata. - """ - # Try the proper API first (works when plugin is registered) - applied = prim.GetAppliedSchemas() - ros2 = [s for s in applied if s.startswith("Ros2")] - if ros2: - return ros2 - - # Fallback: read the raw apiSchemas metadata listOp and extract - # the composed explicit items (result of all prepend/append/delete ops) - meta = prim.GetMetadata("apiSchemas") - if meta is None: - return [] - items = list(meta.explicitItems) if meta.explicitItems else [] - return [s for s in items if s.startswith("Ros2")] - - -def get_ros2_attributes(prim): - """Read all ros2:* authored attributes from a prim.""" - attrs = {} - for attr in prim.GetAttributes(): - name = attr.GetName() - if name.startswith("ros2:"): - value = attr.Get() - authored = attr.IsAuthored() - attrs[name] = (value, authored) - return attrs - - -def traverse_ros2_interfaces(stage_path): - """Load a USD stage and print all ROS 2 interface schemas found.""" - stage = Usd.Stage.Open(stage_path) - if not stage: - print(f"ERROR: Could not open stage: {stage_path}") - return 1 - - print(f"=== ROS 2 Interface Summary for {stage_path} ===") - print(f"Stage up axis: {stage.GetMetadata('upAxis')}") - print(f"Stage meters/unit: {stage.GetMetadata('metersPerUnit')}") - print() - - # Collect prims grouped by schema type - schema_prims = defaultdict(list) - total = 0 - - for prim in Usd.PrimRange(stage.GetPseudoRoot()): - ros2_schemas = get_ros2_schemas(prim) - if not ros2_schemas: - continue - total += 1 - attrs = get_ros2_attributes(prim) - for schema in ros2_schemas: - schema_prims[schema].append((prim.GetPath(), attrs)) - - print(f"Found {total} prims with Ros2 API schemas\n") - - # Print grouped by schema type - for schema in sorted(schema_prims.keys()): - prims = schema_prims[schema] - print(f"--- {schema} ({len(prims)} prim{'s' if len(prims) != 1 else ''}) ---") - for path, attrs in prims: - print(f" {path}") - for attr_name in sorted(attrs.keys()): - value, authored = attrs[attr_name] - marker = "" if authored else " (fallback)" - print(f" {attr_name} = {value!r}{marker}") - print() - - return 0 - - -if __name__ == "__main__": - stage_path = sys.argv[1] if len(sys.argv) > 1 else "../examples/otto600/OTTO600.usda" - sys.exit(traverse_ros2_interfaces(stage_path)) From 0ab0ec37caf4f0e3c4948c4b1547357117883194 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Fri, 27 Mar 2026 14:59:57 +0100 Subject: [PATCH 045/111] use REP-XXXX placeholder for now MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- rep.md | 2 +- schema/schema.usda | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/rep.md b/rep.md index 325190e..8fcb0f5 100644 --- a/rep.md +++ b/rep.md @@ -280,7 +280,7 @@ OpenUSD and robotics XML formats (URDF, SDF, MJCF) are fundamentally mismatched The normative OpenUSD schema definition for all `Ros2*API` schemas is provided in `schema/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. ### Compliance Checker -A REP-2040 compliance checker is to be developed and shared with the community. The tool will provide validation of all REP recommendations for OpenUSD assets and supply actionable feedback for the user for every violation or non-conformance. +A REP-XXXX compliance checker is to be developed and shared with the community. The tool will provide validation of all REP recommendations for OpenUSD assets and supply actionable feedback for the user for every violation or non-conformance. ## References * **[NVIDIA-ETL-PIPELINE]** NVIDIA, Intrinsic, Disney Research. "Using OpenUSD for Modular and Scalable Robotic Simulation and Development". URL: `https://developer.nvidia.com/blog/using-openusd-for-modular-and-scalable-robotic-simulation-and-development/` diff --git a/schema/schema.usda b/schema/schema.usda index d80cd64..2641b6d 100644 --- a/schema/schema.usda +++ b/schema/schema.usda @@ -2,7 +2,7 @@ ( "ROS 2 Integration Schemas for OpenUSD Simulation Asset Interoperability." " Defines declarative, engine-agnostic API schemas for ROS 2 interfaces" - " as specified in REP-2040, Section 2." + " as specified in REP-XXXX, Section 2." subLayers = [ @usd/schema.usda@ ] From 488c9f36b92bbe28ab815443a45aacf3192e8bd2 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Fri, 27 Mar 2026 15:50:41 +0100 Subject: [PATCH 046/111] add section for MimicApi MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- rep.md | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/rep.md b/rep.md index 8fcb0f5..bc4c952 100644 --- a/rep.md +++ b/rep.md @@ -123,6 +123,11 @@ OpenUSD's native instancing mechanisms are designed for repetitive visual and st * *Kinematic Bodies:* Moving bodies that are animated but not dynamically driven by physics should set the physics:kinematicEnabled attribute to true. * *Dummy Frames:* Non-physical dummy frames (e.g., `camera_optical_frame`) must not possess a `PhysicsRigidBodyAPI`. They should be tracked using the `Ros2FrameAPI` as defined in Section 2.8. * **Inertia Representation:** Unlike URDF and SDFormat's 6-value symmetric matrix, OpenUSD requires an eigendecomposed inertia tensor. Converters must mathematically decompose the source matrix into physics:diagonalInertia (eigenvalues) and physics:principalAxes (quaternion). This native decomposed form is the strict single source of truth; custom 6-value array attributes must not be authored or parsed. +* **Mimic Joints:** Joints whose position is a linear function of another joint (e.g., parallel gripper fingers, coupled mechanisms) must declare the coupling declaratively using a `MimicJointAPI` applied to the follower joint. The coupling applies to any single-DOF joint type (revolute, prismatic, etc.) and operates on the joint's native positional value. + * `rel mimic:joint`: Relationship to the source joint. Must use a USD relationship (not a string attribute) to ensure correct path remapping under composition arcs. + * `float mimic:multiplier` (Default: `1.0`): Scale factor. `follower_position = multiplier * source_position + offset`. + * `float mimic:offset` (Default: `0.0`): Constant offset in the source joint's native units. + * *Note: UsdPhysics does not currently provide a joint coupling mechanism. This schema fills that gap. Should AOUSD/ASWF standardize an equivalent under `UsdPhysics`, this REP would adopt the upstream schema.* * **Deformable Bodies:** A vendor-neutral schema for deformable bodies is not yet ratified. Assets must isolate deformable soft-body physics into feature layer for specific domain or vendor (see Section 1.2.1). The asset's default variant must provide a rigid-body fallback approximation for interoperability. #### 1.3.1 Collisions From 0e1b6c0a667993245732a596cefd759fdef67f0d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Mon, 30 Mar 2026 17:29:23 +0200 Subject: [PATCH 047/111] limit to Revolute and Prismatic Joints MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- rep.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rep.md b/rep.md index bc4c952..12f0884 100644 --- a/rep.md +++ b/rep.md @@ -123,7 +123,7 @@ OpenUSD's native instancing mechanisms are designed for repetitive visual and st * *Kinematic Bodies:* Moving bodies that are animated but not dynamically driven by physics should set the physics:kinematicEnabled attribute to true. * *Dummy Frames:* Non-physical dummy frames (e.g., `camera_optical_frame`) must not possess a `PhysicsRigidBodyAPI`. They should be tracked using the `Ros2FrameAPI` as defined in Section 2.8. * **Inertia Representation:** Unlike URDF and SDFormat's 6-value symmetric matrix, OpenUSD requires an eigendecomposed inertia tensor. Converters must mathematically decompose the source matrix into physics:diagonalInertia (eigenvalues) and physics:principalAxes (quaternion). This native decomposed form is the strict single source of truth; custom 6-value array attributes must not be authored or parsed. -* **Mimic Joints:** Joints whose position is a linear function of another joint (e.g., parallel gripper fingers, coupled mechanisms) must declare the coupling declaratively using a `MimicJointAPI` applied to the follower joint. The coupling applies to any single-DOF joint type (revolute, prismatic, etc.) and operates on the joint's native positional value. +* **Mimic Joints:** Joints whose position is a linear function of another joint (e.g., parallel gripper fingers, coupled mechanisms) must declare the coupling declaratively using `MimicJointAPI`, a **SingleApply** API schema applied to the follower joint. `MimicJointAPI` must only be applied to `UsdPhysicsRevoluteJoint` or `UsdPhysicsPrismaticJoint` prims. The coupling operates on the joint's native positional value. * `rel mimic:joint`: Relationship to the source joint. Must use a USD relationship (not a string attribute) to ensure correct path remapping under composition arcs. * `float mimic:multiplier` (Default: `1.0`): Scale factor. `follower_position = multiplier * source_position + offset`. * `float mimic:offset` (Default: `0.0`): Constant offset in the source joint's native units. From 1711016b424789b326cf5a3bed5560c18624e193 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Mon, 30 Mar 2026 18:29:19 +0200 Subject: [PATCH 048/111] allow DAGs, prohibit cycles MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- rep.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rep.md b/rep.md index 12f0884..e067d8e 100644 --- a/rep.md +++ b/rep.md @@ -124,7 +124,7 @@ OpenUSD's native instancing mechanisms are designed for repetitive visual and st * *Dummy Frames:* Non-physical dummy frames (e.g., `camera_optical_frame`) must not possess a `PhysicsRigidBodyAPI`. They should be tracked using the `Ros2FrameAPI` as defined in Section 2.8. * **Inertia Representation:** Unlike URDF and SDFormat's 6-value symmetric matrix, OpenUSD requires an eigendecomposed inertia tensor. Converters must mathematically decompose the source matrix into physics:diagonalInertia (eigenvalues) and physics:principalAxes (quaternion). This native decomposed form is the strict single source of truth; custom 6-value array attributes must not be authored or parsed. * **Mimic Joints:** Joints whose position is a linear function of another joint (e.g., parallel gripper fingers, coupled mechanisms) must declare the coupling declaratively using `MimicJointAPI`, a **SingleApply** API schema applied to the follower joint. `MimicJointAPI` must only be applied to `UsdPhysicsRevoluteJoint` or `UsdPhysicsPrismaticJoint` prims. The coupling operates on the joint's native positional value. - * `rel mimic:joint`: Relationship to the source joint. Must use a USD relationship (not a string attribute) to ensure correct path remapping under composition arcs. + * `rel mimic:joint`: Relationship to the source joint. Must use a USD relationship (not a string attribute) to ensure correct path remapping under composition arcs. Mimic relationships must form a Directed Acyclic Graph (DAG); chained couplings are valid, but cycles are prohibited. * `float mimic:multiplier` (Default: `1.0`): Scale factor. `follower_position = multiplier * source_position + offset`. * `float mimic:offset` (Default: `0.0`): Constant offset in the source joint's native units. * *Note: UsdPhysics does not currently provide a joint coupling mechanism. This schema fills that gap. Should AOUSD/ASWF standardize an equivalent under `UsdPhysics`, this REP would adopt the upstream schema.* From da78e73689d70707b5693b58f316344110754712 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Mon, 30 Mar 2026 15:39:37 +0200 Subject: [PATCH 049/111] Update rep.md Updated to reflect ETL developments in 6.0 Signed-off-by: Adam Dabrowski --- rep.md | 16 ++++++++++++---- 1 file changed, 12 insertions(+), 4 deletions(-) diff --git a/rep.md b/rep.md index e067d8e..4f1cd2e 100644 --- a/rep.md +++ b/rep.md @@ -68,10 +68,14 @@ This REP endorses the ETL composition architecture developed collaboratively by As illustrated in Figure 1, assets should be divided into functional layers composed via References and Payloads: -* **Asset Source & Transformation (The Base Layer):** The raw CAD data (`asset_base.usd`) is optimized into simulation-ready geometry (`asset_sim_optimized.usd`). This layer contains native OpenUSD schemas (`UsdGeom`, `UsdShade`). +* **Asset Source & Transformation (The Base Layer):** The raw (e.g. CAD) data is optimized and decomposed into granular, functional files to maximize deduplication and performance. This layer contains core native OpenUSD schemas and should be structured as follows: + * `geometries.usd`: Contains pure mesh topology and vertices (no physics, no schemas). Most geometries should use the binary format (`.usdc`). + * `materials.usd`: Contains pure material definitions (`UsdShade`) and look-dev. + * `instances.usd` (Optional, recommended): Assembles geometries and materials via references. + * `base.usd`: The pure kinematic hierarchy (Xforms), referencing the underlying instances and geometries without physical or execution logic. * **Features (The Domain-Specific Layers):** Domain metadata is isolated into specific overlay files that reference the Base Layer. For example, `asset_physics.usd` contains the rigid bodies and joints, while `asset_ros.usd` contains the `Ros2*API` schemas defined in this REP. * **Entry Point (`asset.usd`):** The final distributed asset is a lightweight interface layer that uses **Payloads** to load the Features. -* **Proprietary Layer:** Asset authors should avoid including heavy, simulator-specific implementations (e.g., proprietary execution graphs) within the interoperable asset package. If unavoidable, they must minimize this proprietary layer (e.g., `asset_isaac.usd`) to what is strictly necessary and keep it isolated as a separate Feature layer. +* **Proprietary Layer:** Asset authors should avoid including heavy, simulator-specific implementations (e.g., proprietary execution graphs) within the interoperable asset package. If unavoidable, they must minimize this proprietary layer (e.g., `isaac.usd`, `o3de.usd`) to what is strictly necessary and keep it isolated as a separate Feature layer. #### 1.2.2 The Composition Model @@ -149,8 +153,12 @@ Collision meshes are not subject to this VariantSet; their fidelity is governed #### 1.3.3 Contact Physics To ensure deterministic contact dynamics across engines, authors must bind a `UsdShadeMaterial` bearing the `UsdPhysicsMaterialAPI` to collision geometries. This material must define `physics:staticFriction`, `physics:dynamicFriction`, and `physics:restitution`. To prevent conflicts with visual shading networks, the physical material must be bound to the collision geometry explicitly using the physics material purpose (`material:binding:physics`), rather than the default all-purpose binding. Because engines utilize distinct friction models, converters must approximate these baseline values into their specific representations (e.g., SDF `` or MJCF ``). -### 1.4 Isolation of vendor-specific extensions -Engine-specific parameters (e.g., solver iterations, GPU tensors) not covered by core OpenUSD schemas must be explicitly namespaced with a vendor prefix (e.g., mujoco:, isaac:). This applies to both formal vendor-supplied API schemas and ad-hoc custom attributes. This proprietary metadata must be strictly isolated within the ETL Pipeline's "Proprietary Layer" (Section 1.2.1) and never authored in the baseline simulation payload. Authors must strive to minimize proprietary layer to strictly necessary. +### 1.4 Isolation of vendor and physics specific extensions + +To guarantee interoperability across different solvers, physical properties and engine-specific parameters must be explicitly decoupled into separate functional layers: + +* **Neutral Physics (`physics.usd`):** A universally shared layer containing exclusively core `UsdPhysics` schemas (rigid bodies, joints, limits, mass properties). This file must strictly adhere to the standard OpenUSD Physics specification and must not contain any vendor-specific extensions. +* **Engine Tuning (`physx.usd`, `mujoco.usd`, `isaac.usd`):** Engine-specific parameters (e.g., proprietary solver iterations, specialized friction models, GPU tensors) not covered by core OpenUSD schemas must be explicitly namespaced with a vendor prefix (e.g., `mujoco:`, `isaac:`). These must be strictly isolated within discrete "Proprietary Layers" (Section 1.2.1) and never authored in the baseline simulation payload or neutral physics layer. Authors must strive to minimize this proprietary layer to what is strictly necessary. --- From 71babea6971ba0e6c6bd10bbd2fdd9dbd0984f1d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Tue, 31 Mar 2026 12:33:30 +0200 Subject: [PATCH 050/111] Remove unnecessary 1.2.6 Names are already guaranteed to conform Signed-off-by: Adam Dabrowski --- rep.md | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/rep.md b/rep.md index 4f1cd2e..c9e82cb 100644 --- a/rep.md +++ b/rep.md @@ -104,10 +104,7 @@ OpenUSD `VariantSets` are the normative mechanism for asset reusability (e.g., e * **Native Composition vs. Custom Prefabs:** The use of custom or vendor-specific string attributes (e.g., `custom string my_sim:prefabPath = "robot.usd"`) to dynamically load, instantiate, or compose assets at runtime is strictly prohibited for interoperable assets. Asset composition must rely purely on native OpenUSD references or payloads. * **FileFormat Plugins:** OpenUSD supports FileFormat plugins (e.g., MuJoCo's `usdMjcf` plugin) to dynamically translate legacy formats into USD stages at runtime. While these plugins are recommended for import pathways, this REP governs the *resulting in-memory OpenUSD data*. Plugins interfacing with the ROS 2 ecosystem must generate stages that conform to the physical hierarchies and API schemas defined in this document. -#### 1.2.6 ROS-Compatible Identifiers -OpenUSD natively enforces strict naming for Prims (they must start with a letter or underscore, followed by alphanumeric characters or underscores: [a-zA-Z_][a-zA-Z0-9_]*). This natively aligns with ROS conventions. Furthermore, Prim names intended to map directly to ROS TF Frames must not contain spaces or special characters that could violate downstream ROS 2 lexical rules. - -#### 1.2.7 Parallel Simulation and Instancing +#### 1.2.6 Parallel Simulation and Instancing OpenUSD's native instancing mechanisms are designed for repetitive visual and structural geometry. They must not be used to clone articulated physics assets to create massive parallel arrays (e.g., for reinforcement learning). * **Canonical Assets:** Authors must distribute a single, self-contained canonical environment. * **Runtime Delegation:** Simulators supporting massive parallelism are expected to handle environment replication natively at runtime via their own APIs. Authors must not bake thousands of physics-enabled clones into the source file. From 9acf9f14273fe14107146781cc65726e81476ad8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Tue, 31 Mar 2026 13:34:13 +0200 Subject: [PATCH 051/111] ROS is ROS 2 Since ROS is EOL, ROS is now used instead of ROS 2 Signed-off-by: Adam Dabrowski --- rep.md | 96 +++++++++++++++++++++++++++++----------------------------- 1 file changed, 48 insertions(+), 48 deletions(-) diff --git a/rep.md b/rep.md index c9e82cb..904ee91 100644 --- a/rep.md +++ b/rep.md @@ -16,19 +16,19 @@ This REP defines a standard schema and strict profile of OpenUSD (Universal Scene Description) for the interchange of robotics simulation assets. The scope includes robots, sensors, static environments (e.g., warehouse racks), and dynamic props. This REP aims to ensure that a single asset functions consistently across: 1. **Simulation and physics engines** (Gazebo, Isaac Sim, Newton, Genesis, MuJoCo, O3DE). -2. **Runtime integrations** (ROS 2 Interfaces). +2. **Runtime integrations** (ROS Interfaces). 3. **Converters and web visualization** (especially glTF 2.0 conversion). To achieve this, the specification addresses three 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 2 interfaces to ensure engine-agnostic runtime behavior. +* **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. ## Motivation The ROS ecosystem chiefly relies on URDF and SDF for describing robots and environments. These formats are almost entirely confined to the ROS and Gazebo ecosystems. OpenUSD has emerged as an industry standard supported by a multitude of tools and allows artists to collaborate with simulation engineers without problematic conversions between a variety of 3D and XML formats. Ensuring OpenUSD works well with ROS integrations across robotics simulators will increase ecosystem interoperability and strengthen ROS's position in physical AI workflows such as synthetic data and generative pipelines. OpenUSD is a powerful format with an extensible architecture allowing it to capture all the semantics of other popular formats. -While OpenUSD adoption is growing quickly, only the core standard specification has been ratified so far, leaving most of what's interesting for robotics uncovered. OpenUSD lacks standardized semantic representations for ROS 2 interfaces and standard rules for mapping to ROS concepts such as frames and TF trees. OpenUSD's flexibility also permits practices that degrade interoperability, such as proprietary extensions, defining execution instead of intent, and overfitting to particular workflows. +While OpenUSD adoption is growing quickly, only the core standard specification has been ratified so far, leaving most of what's interesting for robotics uncovered. OpenUSD lacks standardized semantic representations for ROS interfaces and standard rules for mapping to ROS concepts such as frames and TF trees. OpenUSD's flexibility also permits practices that degrade interoperability, such as proprietary extensions, defining execution instead of intent, and overfitting to particular workflows. OpenUSD is championed by the Alliance for OpenUSD (AOUSD) and the ASWF USD Working Group. NVIDIA also plays a key role both as a founding member of AOUSD and in developing OpenUSD for robotics through Omniverse, Isaac Sim and Newton. This REP builds on top of great work done by all these entities, extending it by addressing what is not yet standardized but urgently needed for OpenUSD interoperability in the ROS simulation ecosystem, and standardizing against practices that result in a vendor lock-in. As such, this REP is designed to adapt upstream standards for the ROS community, while serving as a reference to influence future decisions by AOUSD and ASWF. @@ -59,7 +59,7 @@ This REP adopts the ASWF Guidelines for Structuring USD Assets. #### 1.2.1 Schema Isolation and Functional Layering (The ETL Pipeline) -To avoid "Unknown Schema" errors in standard 3D authoring tools (e.g., Blender, Maya) and to ensure assets remain modular, functional layering (Extract-Transform-Load) should be utilized for ROS 2 interfaces, physics, and simulator-specific tooling syntax. +To avoid "Unknown Schema" errors in standard 3D authoring tools (e.g., Blender, Maya) and to ensure assets remain modular, functional layering (Extract-Transform-Load) should be utilized for ROS interfaces, physics, and simulator-specific tooling syntax. This REP endorses the ETL composition architecture developed collaboratively by NVIDIA, Intrinsic, and Disney Research for OpenUSD robotics assets. @@ -73,7 +73,7 @@ As illustrated in Figure 1, assets should be divided into functional layers comp * `materials.usd`: Contains pure material definitions (`UsdShade`) and look-dev. * `instances.usd` (Optional, recommended): Assembles geometries and materials via references. * `base.usd`: The pure kinematic hierarchy (Xforms), referencing the underlying instances and geometries without physical or execution logic. -* **Features (The Domain-Specific Layers):** Domain metadata is isolated into specific overlay files that reference the Base Layer. For example, `asset_physics.usd` contains the rigid bodies and joints, while `asset_ros.usd` contains the `Ros2*API` schemas defined in this REP. +* **Features (The Domain-Specific Layers):** Domain metadata is isolated into specific overlay files that reference the Base Layer. For example, `asset_physics.usd` contains the rigid bodies and joints, while `asset_ros.usd` contains the `Ros*API` schemas defined in this REP. * **Entry Point (`asset.usd`):** The final distributed asset is a lightweight interface layer that uses **Payloads** to load the Features. * **Proprietary Layer:** Asset authors should avoid including heavy, simulator-specific implementations (e.g., proprietary execution graphs) within the interoperable asset package. If unavoidable, they must minimize this proprietary layer (e.g., `isaac.usd`, `o3de.usd`) to what is strictly necessary and keep it isolated as a separate Feature layer. @@ -90,19 +90,19 @@ To guarantee that simulation assets remain self-contained, portable, and predict * **[V] VariantSets:** Permitted and encouraged for asset reusability (see Section 1.2.3). * **[R] References:** Permitted for logical assembly (e.g., composing a robot by referencing an independent `arm.usd` and `base.usd`). * **[P] Payloads (The Payload Pattern):** Heavy data (high-resolution meshes, point clouds, large textures) must be referenced via Payloads rather than standard References. - * Payloads must not gate joint or link prims themselves. The kinematic topology (Prims bearing `PhysicsRigidBodyAPI`, `PhysicsJoint` schemas, and `Ros2*API` schemas) must reside in the primarily loaded scene graph (e.g., via Local authoring or standard References). + * Payloads must not gate joint or link prims themselves. The kinematic topology (Prims bearing `PhysicsRigidBodyAPI`, `PhysicsJoint` schemas, and `Ros*API` schemas) must reside in the primarily loaded scene graph (e.g., via Local authoring or standard References). * The Payload should solely encapsulate the nested geometric and material data. This enables ROS parsers and web converters to traverse the lightweight kinematic tree efficiently without loading heavy buffers. #### 1.2.4 Variants OpenUSD `VariantSets` are the normative mechanism for asset reusability (e.g., encapsulating multiple furniture styles, different robot end-effectors, or optional sensor suites within a single asset). * **Default Variant Fallback:** Any asset utilizing `VariantSets` must author a default variant selection. This ensures that if the asset is loaded by a simulator or CI/CD pipeline without explicit variant overrides, it resolves to a valid, predictable physical and visual state. -* **ROS Interface Resolution:** A change in a variant selection may add or remove Prims containing `Ros2*API` schemas (e.g., swapping a generic robot head for a sensor-equipped head). Simulators and tooling must only evaluate and spawn ROS interfaces that are active within the currently resolved variant state of the stage. +* **ROS Interface Resolution:** A change in a variant selection may add or remove Prims containing `Ros*API` schemas (e.g., swapping a generic robot head for a sensor-equipped head). Simulators and tooling must only evaluate and spawn ROS interfaces that are active within the currently resolved variant state of the stage. #### 1.2.5 Asset Management * **Path Resolution:** Internal references must use relative paths (`./geo/mesh.usdc`). For distributed, highly interoperable assets, all file dependencies should be self-contained and rely exclusively on relative paths. * **ROS packages:** External dependencies to other ROS packages must use the package:// URI scheme, and should be contained in ROS-specific .usd files in the ETL pipeline. Asset authors must be aware that resolving these URIs requires the host simulator or tool to implement a custom OpenUSD ArResolver plugin. Absolute paths and proprietary schemes (e.g., omniverse://) are strictly prohibited in distributed assets. * **Native Composition vs. Custom Prefabs:** The use of custom or vendor-specific string attributes (e.g., `custom string my_sim:prefabPath = "robot.usd"`) to dynamically load, instantiate, or compose assets at runtime is strictly prohibited for interoperable assets. Asset composition must rely purely on native OpenUSD references or payloads. -* **FileFormat Plugins:** OpenUSD supports FileFormat plugins (e.g., MuJoCo's `usdMjcf` plugin) to dynamically translate legacy formats into USD stages at runtime. While these plugins are recommended for import pathways, this REP governs the *resulting in-memory OpenUSD data*. Plugins interfacing with the ROS 2 ecosystem must generate stages that conform to the physical hierarchies and API schemas defined in this document. +* **FileFormat Plugins:** OpenUSD supports FileFormat plugins (e.g., MuJoCo's `usdMjcf` plugin) to dynamically translate legacy formats into USD stages at runtime. While these plugins are recommended for import pathways, this REP governs the *resulting in-memory OpenUSD data*. Plugins interfacing with the ROS ecosystem must generate stages that conform to the physical hierarchies and API schemas defined in this document. #### 1.2.6 Parallel Simulation and Instancing OpenUSD's native instancing mechanisms are designed for repetitive visual and structural geometry. They must not be used to clone articulated physics assets to create massive parallel arrays (e.g., for reinforcement learning). @@ -122,7 +122,7 @@ OpenUSD's native instancing mechanisms are designed for repetitive visual and st * Static Environments: Fixed props (e.g., walls, racks) must possess a PhysicsCollisionAPI but omit the PhysicsRigidBodyAPI. OpenUSD implicitly treats these as having zero velocity and infinite mass. * Robot Anchors: A fixed robot base must have a valid mass > 0 and be anchored via a UsdPhysicsFixedJoint with an empty physics:body0 relationship (which natively represents the world). * *Kinematic Bodies:* Moving bodies that are animated but not dynamically driven by physics should set the physics:kinematicEnabled attribute to true. - * *Dummy Frames:* Non-physical dummy frames (e.g., `camera_optical_frame`) must not possess a `PhysicsRigidBodyAPI`. They should be tracked using the `Ros2FrameAPI` as defined in Section 2.8. + * *Dummy Frames:* Non-physical dummy frames (e.g., `camera_optical_frame`) must not possess a `PhysicsRigidBodyAPI`. They should be tracked using the `RosFrameAPI` as defined in Section 2.8. * **Inertia Representation:** Unlike URDF and SDFormat's 6-value symmetric matrix, OpenUSD requires an eigendecomposed inertia tensor. Converters must mathematically decompose the source matrix into physics:diagonalInertia (eigenvalues) and physics:principalAxes (quaternion). This native decomposed form is the strict single source of truth; custom 6-value array attributes must not be authored or parsed. * **Mimic Joints:** Joints whose position is a linear function of another joint (e.g., parallel gripper fingers, coupled mechanisms) must declare the coupling declaratively using `MimicJointAPI`, a **SingleApply** API schema applied to the follower joint. `MimicJointAPI` must only be applied to `UsdPhysicsRevoluteJoint` or `UsdPhysicsPrismaticJoint` prims. The coupling operates on the joint's native positional value. * `rel mimic:joint`: Relationship to the source joint. Must use a USD relationship (not a string attribute) to ensure correct path remapping under composition arcs. Mimic relationships must form a Directed Acyclic Graph (DAG); chained couplings are valid, but cycles are prohibited. @@ -159,77 +159,77 @@ To guarantee interoperability across different solvers, physical properties and --- -## 2. ROS 2 Integration Schemas +## 2. ROS Integration Schemas Neither OpenUSD nor glTF 2.0 currently standardize the specification of ROS interfaces. This section defines a set of declarative, engine-agnostic API schemas (of type `SingleApply`). Simulators are responsible for reading these schemas and generating their respective underlying execution logic. -### 2.1 The ROS 2 Context (`Ros2ContextAPI`) +### 2.1 The ROS Context (`RosContextAPI`) The root prim of a ROS-interfaced simulation asset may define its context namespace. -* `string ros2:context:namespace`: Prefixes all topics within this scope (e.g., `/robot_1`). The namespace is additive in the asset hierarchy and with a top-level namespace set during simulation deployment (e.g., via the `SpawnEntity` service). -* `int ros2:context:domain_id` (Optional): Overrides the default ROS Domain ID for interfaces descending from this context. -* `string ros2:context:parent_frame` (Optional, Default: `"world"`): Defines the parent `frame_id` used when the simulator broadcasts the ground-truth transform of this context's root prim. It is only valid for the top-most context in the resolved USD Stage and ignored otherwise. +* `string ros:context:namespace`: Prefixes all topics within this scope (e.g., `/robot_1`). The namespace is additive in the asset hierarchy and with a top-level namespace set during simulation deployment (e.g., via the `SpawnEntity` service). +* `int ros:context:domain_id` (Optional): Overrides the default ROS Domain ID for interfaces descending from this context. +* `string ros:context:parent_frame` (Optional, Default: `"world"`): Defines the parent `frame_id` used when the simulator broadcasts the ground-truth transform of this context's root prim. It is only valid for the top-most context in the resolved USD Stage and ignored otherwise. ### 2.2 Interface Placement -ROS 2 interface schemas (`Ros2TopicAPI`, `Ros2ServiceAPI`, `Ros2ActionAPI`) must be applied to prims according to these placement rules: +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 `Ros2ContextAPI`. +* **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`. * **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 `Ros2*API` schemas are part of the lightweight kinematic/interface graph and must be traversable without loading geometry payloads. +* **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. ### 2.3 Interface Resolution For all schema types (Topics, Services, Actions) defined below: -* **Type Resolution:** Tooling and compliant simulators must attempt to resolve the `ros2:*:type` string (e.g., `sensor_msgs/msg/Image`) dynamically against the sourced ROS 2 environment. If the interface type is not found, the simulator must safely disable that specific interface, allow the rest of the asset to function normally, and emit a distinct warning/error. -* **Name Validation:** All `ros2:*:name` values must strictly adhere to ROS 2 topic naming rules (alphanumeric, underscores, and forward slashes only; cannot start with a number). +* **Type Resolution:** Tooling and compliant simulators must attempt to resolve the `ros:*:type` string (e.g., `sensor_msgs/msg/Image`) dynamically against the sourced ROS environment. If the interface type is not found, the simulator must safely disable that specific interface, allow the rest of the asset to function normally, and emit a distinct warning/error. +* **Name Validation:** All `ros:*:name` values must strictly adhere to ROS topic naming rules (alphanumeric, underscores, and forward slashes only; cannot start with a number). -### 2.4 Topic Interface (`Ros2TopicAPI`) +### 2.4 Topic Interface (`RosTopicAPI`) Applies to Prims that exchange streaming ROS data. **Core Attributes (Required):** -* `token ros2:topic:role`: Values: `["publisher", "subscription"]`. -* `string ros2:topic:name`: The topic name relative to the active namespace. -* `string ros2:topic:type`: The ROS message type. -* `double ros2:topic:publish_rate`: Target publication frequency in Hz. Required for publishers; ignored for subscriptions. +* `token ros:topic:role`: Values: `["publisher", "subscription"]`. +* `string ros:topic:name`: The topic name relative to the active namespace. +* `string ros:topic:type`: The ROS message type. +* `double ros:topic:publish_rate`: Target publication frequency in Hz. Required for publishers; ignored for subscriptions. **Quality of Service (QoS):** Maps directly to `rmw_qos_profile_t` policies. If an attribute is omitted, simulators must assume the specified defaults. *(Note: As per REP 2003, simulated sensors should default to `"system_default"` which maps to best-effort, while map publishers should use `"transient_local"`).* -* `bool ros2:topic:qos:match_publisher` (Optional, Default: `false`). For subscriptions only. If `true`, the simulator bridge must attempt to use ROS 2 QoS matching to adapt to the discovered publisher, ignoring explicit reliability/durability settings. -* `token ros2:topic:qos:reliability`: Values: `["system_default", "reliable", "best_effort"]`. (Default: `"system_default"`). -* `token ros2:topic:qos:durability`: Values: `["system_default", "transient_local", "volatile"]`. (Default: `"system_default"`). -* `token ros2:topic:qos:history`: Values: `["system_default", "keep_last", "keep_all"]`. (Default: `"system_default"`). -* `int ros2:topic:qos:depth`: Queue size. Evaluated only when history is `keep_last`. (Default: `10`). +* `bool ros:topic:qos:match_publisher` (Optional, Default: `false`). For subscriptions only. If `true`, the simulator bridge must attempt to use ROS QoS matching to adapt to the discovered publisher, ignoring explicit reliability/durability settings. +* `token ros:topic:qos:reliability`: Values: `["system_default", "reliable", "best_effort"]`. (Default: `"system_default"`). +* `token ros:topic:qos:durability`: Values: `["system_default", "transient_local", "volatile"]`. (Default: `"system_default"`). +* `token ros:topic:qos:history`: Values: `["system_default", "keep_last", "keep_all"]`. (Default: `"system_default"`). +* `int ros:topic:qos:depth`: Queue size. Evaluated only when history is `keep_last`. (Default: `10`). -### 2.5 Service Interface (`Ros2ServiceAPI`) +### 2.5 Service Interface (`RosServiceAPI`) Applies to Prims handling synchronous requests (e.g., blinking lights). -* `token ros2:service:role`: Values: `["server", "client"]`. (Simulation assets are typically `server`). -* `string ros2:service:name`: The service name. -* `string ros2:service:type`: The service type (e.g., `std_srvs/srv/SetBool`). +* `token ros:service:role`: Values: `["server", "client"]`. (Simulation assets are typically `server`). +* `string ros:service:name`: The service name. +* `string ros:service:type`: The service type (e.g., `std_srvs/srv/SetBool`). -### 2.6 Action Interface (`Ros2ActionAPI`) +### 2.6 Action Interface (`RosActionAPI`) Applies to Prims handling asynchronous, long-running behaviors. -* `token ros2:action:role`: Values: `["server", "client"]`. (Simulation assets are typically `server`). -* `string ros2:action:name`: The action name. -* `string ros2:action:type`: The action type (e.g., `control_msgs/action/FollowJointTrajectory`). +* `token ros:action:role`: Values: `["server", "client"]`. (Simulation assets are typically `server`). +* `string ros:action:name`: The action name. +* `string ros:action:type`: The action type (e.g., `control_msgs/action/FollowJointTrajectory`). -### 2.7 Frame Publishing and TF2 (`Ros2FrameAPI`) -Mapping a deeply nested OpenUSD scene graph directly to a ROS 2 TF tree can cause significant performance overhead. To prevent flooding the `/tf` topic with generic physical props (e.g., warehouse boxes), compliant simulators should not broadcast transforms for every `PhysicsRigidBodyAPI`. +### 2.7 Frame Publishing and TF2 (`RosFrameAPI`) +Mapping a deeply nested OpenUSD scene graph directly to a ROS TF tree can cause significant performance overhead. To prevent flooding the `/tf` topic with generic physical props (e.g., warehouse boxes), compliant simulators should not broadcast transforms for every `PhysicsRigidBodyAPI`. Instead, simulators should follow a hybrid implicit/explicit approach for broadcasting `tf2` transforms: * **Implicit TF Broadcasting (The Asset Tree):** Simulators should automatically infer and broadcast TF frames (using the ROS-validated Prim name) for Prims that represent a ROS interface structure: - 1. **The ROS Root:** Any Prim possessing the `Ros2ContextAPI` (often the `base_link`). + 1. **The ROS Root:** Any Prim possessing the `RosContextAPI` (often the `base_link`). 2. **Kinematic Chains:** Any Prim possessing a `PhysicsRigidBodyAPI` that is connected (directly or recursively) via a `UsdPhysicsJoint` to a Prim already in the TF tree. This captures robot arms and wheeled bases automatically. * **Routing Rule:** If the implicit frame is connected to its parent via a `PhysicsFixedJoint`, or has no joint but is rigidly parented in the USD hierarchy, the simulator must broadcast it to `/tf_static`. All movable joint connections must be broadcast to `/tf`. - * Prims bearing only `Ros2TopicAPI`, `Ros2ServiceAPI`, or `Ros2ActionAPI` do not generate TF frames. An interface prim's `frame_id` is determined by its nearest ancestor that is a TF frame (implicit or explicit). + * Prims bearing only `RosTopicAPI`, `RosServiceAPI`, or `RosActionAPI` do not generate TF frames. An interface prim's `frame_id` is determined by its nearest ancestor that is a TF frame (implicit or explicit). -* **Explicit TF Broadcasting (`Ros2FrameAPI`):** To publish TFs for non-physical dummy frames (e.g., a kinematic `grasp_point`, a `camera_optical_frame`), asset authors must apply the `Ros2FrameAPI` schema to the target `UsdGeomXform` Prim. - * `string ros2:frame:id` (Optional): Overrides the TF frame name. If omitted, the validated Prim name is used. - * `bool ros2:frame:static` (Optional, Default: `true`): Defines the broadcast destination. If `true`, the simulator must broadcast the frame to `/tf_static` relative to its USD parent. If `false` (e.g., an Xform animated by USD TimeSamples), it must be broadcast to `/tf`. +* **Explicit TF Broadcasting (`RosFrameAPI`):** To publish TFs for non-physical dummy frames (e.g., a kinematic `grasp_point`, a `camera_optical_frame`), asset authors must apply the `RosFrameAPI` schema to the target `UsdGeomXform` Prim. + * `string ros:frame:id` (Optional): Overrides the TF frame name. If omitted, the validated Prim name is used. + * `bool ros:frame:static` (Optional, Default: `true`): Defines the broadcast destination. If `true`, the simulator must broadcast the frame to `/tf_static` relative to its USD parent. If `false` (e.g., an Xform animated by USD TimeSamples), it must be broadcast to `/tf`. Note: The broadcast frequency of TF frames is an implementation detail left to the simulator's runtime configuration. ### 2.8 Optical Frames -OpenUSD cameras natively face the -Z axis, whereas ROS 2 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 Ros2TopicAPI and Ros2FrameAPI schemas must be applied exclusively to this optical frame, ensuring deterministic data orientation in RViz. +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. --- @@ -261,7 +261,7 @@ Procedural texture graphs (noise generation, math nodes, node graphs) are not in * **Manifold topology:** Collision meshes must be watertight (closed, manifold) and free of self-intersections to ensure stable physics and mass derivation. Non-manifold geometry (e.g., open edges) is strictly limited to purely visual meshes. ### 3.5 Instanceable Leaves -Repetitive geometry (bolts, LED arrays on a sensor) must utilize native OpenUSD instancing to minimize memory footprint. Authors must only instance leaf geometry (visuals and colliders), not logical Prims containing PhysicsRigidBodyAPI, Joints, or Ros2*API schemas, as OpenUSD instance proxies obscure child prims from relationship targeting. Authors must use one of two mechanisms to ensure correct glTF conversion: +Repetitive geometry (bolts, LED arrays on a sensor) must utilize native OpenUSD instancing to minimize memory footprint. Authors must only instance leaf geometry (visuals and colliders), not logical Prims containing PhysicsRigidBodyAPI, Joints, or Ros*API schemas, as OpenUSD instance proxies obscure child prims from relationship targeting. Authors must use one of two mechanisms to ensure correct glTF conversion: * **Scenegraph instancing (`instanceable=true`):** Used for identical structural components (e.g., bolts). Note: The OpenUSD specification requires the prim to compose its geometry via a composition arc (Reference or Payload) for this flag to be valid. Converters must map this to native glTF Node sharing (multiple nodes referencing a single mesh index). * **Point instancing (`UsdGeomPointInstancer`):** Used for massive arrays of atomic meshes (e.g., LED grids, warehouse clutter). It scatters a prototype using flat arrays of transforms. Converters must map this directly to the glTF EXT_mesh_gpu_instancing extension. @@ -281,13 +281,13 @@ While OpenUSD natively handles structural variants, many of the simulation tools OpenUSD and robotics XML formats (URDF, SDF, MJCF) are fundamentally mismatched paradigms. Because OpenUSD lacks native schemas for domain-specific data (e.g., URDF ``, MJCF ``), conversions are inherently lossy. Exporters must adhere to the following: * **Payload Resolution:** The active simulation payload (kinematics, inertia, colliders) is the extraction priority. OpenUSD composition arcs and instance proxies must be fully baked into explicit geometry and transforms, never discarded. -* **API Translation:** Ros2*API schemas must map exclusively to modern extension blocks (e.g., SDF ``, MJCF ``). Obsolete approaches such as injecting legacy `` tags into URDF are not allowed. +* **API Translation:** Ros*API schemas must map exclusively to modern extension blocks (e.g., SDF ``, MJCF ``). Obsolete approaches such as injecting legacy `` 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. ## Tools ### Schema Definition -The normative OpenUSD schema definition for all `Ros2*API` schemas is provided in `schema/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. +The normative OpenUSD schema definition for all `Ros*API` schemas is provided in `schema/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. ### Compliance Checker A REP-XXXX compliance checker is to be developed and shared with the community. The tool will provide validation of all REP recommendations for OpenUSD assets and supply actionable feedback for the user for every violation or non-conformance. From f3fcfec771daf8e5e66b7d0bb229bc9bdb34312b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Tue, 31 Mar 2026 14:34:29 +0200 Subject: [PATCH 052/111] add subsection on collision filtering MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- rep.md | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/rep.md b/rep.md index 904ee91..6dba86d 100644 --- a/rep.md +++ b/rep.md @@ -147,7 +147,14 @@ To ensure assets function across high-end renderers (Isaac Sim, O3DE), CPU-bound Collision meshes are not subject to this VariantSet; their fidelity is governed by the `collision_fidelity` VariantSet (Section 1.3.1). -#### 1.3.3 Contact Physics +#### 1.3.3 Self-Collision Filtering +`UsdPhysicsJoint` disables collisions between its connected links by default (`physics:collisionEnabled = false`). Non-adjacent links are not covered by this mechanism and require explicit filtering: +* **`UsdPhysicsCollisionGroup`** (recommended): Assets should define a collision group that references itself via `physics:filteredGroups` to disable all intra-robot collisions. Since both collection membership and filtered group targets are relationships, composition automatically remaps them per instance. Where selective self-collision is required, assets may use multiple groups with targeted filtering. +* **`UsdPhysicsFilteredPairsAPI`**: May be used for fine-grained pairwise exceptions. Takes precedence over group filtering. + +Baseline collision filtering must use standard `UsdPhysics` schemas. Engine-specific mechanisms (e.g., PhysX filter shaders, MuJoCo `contype`/`conaffinity`) may augment but must not replace this baseline, and must be isolated in the vendor-specific layer (Section 1.4). + +#### 1.3.4 Contact Physics To ensure deterministic contact dynamics across engines, authors must bind a `UsdShadeMaterial` bearing the `UsdPhysicsMaterialAPI` to collision geometries. This material must define `physics:staticFriction`, `physics:dynamicFriction`, and `physics:restitution`. To prevent conflicts with visual shading networks, the physical material must be bound to the collision geometry explicitly using the physics material purpose (`material:binding:physics`), rather than the default all-purpose binding. Because engines utilize distinct friction models, converters must approximate these baseline values into their specific representations (e.g., SDF `` or MJCF ``). ### 1.4 Isolation of vendor and physics specific extensions From a60f2994bcdefb850f2a1c6a94742f4b00720bd5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Tue, 31 Mar 2026 14:59:07 +0200 Subject: [PATCH 053/111] make concise MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- rep.md | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/rep.md b/rep.md index 6dba86d..437fece 100644 --- a/rep.md +++ b/rep.md @@ -148,11 +148,7 @@ To ensure assets function across high-end renderers (Isaac Sim, O3DE), CPU-bound Collision meshes are not subject to this VariantSet; their fidelity is governed by the `collision_fidelity` VariantSet (Section 1.3.1). #### 1.3.3 Self-Collision Filtering -`UsdPhysicsJoint` disables collisions between its connected links by default (`physics:collisionEnabled = false`). Non-adjacent links are not covered by this mechanism and require explicit filtering: -* **`UsdPhysicsCollisionGroup`** (recommended): Assets should define a collision group that references itself via `physics:filteredGroups` to disable all intra-robot collisions. Since both collection membership and filtered group targets are relationships, composition automatically remaps them per instance. Where selective self-collision is required, assets may use multiple groups with targeted filtering. -* **`UsdPhysicsFilteredPairsAPI`**: May be used for fine-grained pairwise exceptions. Takes precedence over group filtering. - -Baseline collision filtering must use standard `UsdPhysics` schemas. Engine-specific mechanisms (e.g., PhysX filter shaders, MuJoCo `contype`/`conaffinity`) may augment but must not replace this baseline, and must be isolated in the vendor-specific layer (Section 1.4). +`UsdPhysicsJoint` disables collisions between its connected links by default (`physics:collisionEnabled = false`). Assets should use `UsdPhysicsCollisionGroup` to define collision group filtering and may use `UsdPhysicsFilteredPairsAPI` for fine-grained exceptions. #### 1.3.4 Contact Physics To ensure deterministic contact dynamics across engines, authors must bind a `UsdShadeMaterial` bearing the `UsdPhysicsMaterialAPI` to collision geometries. This material must define `physics:staticFriction`, `physics:dynamicFriction`, and `physics:restitution`. To prevent conflicts with visual shading networks, the physical material must be bound to the collision geometry explicitly using the physics material purpose (`material:binding:physics`), rather than the default all-purpose binding. Because engines utilize distinct friction models, converters must approximate these baseline values into their specific representations (e.g., SDF `` or MJCF ``). From f4509f449dde88d87bc2ac5682c0977d78fa35d3 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Tue, 31 Mar 2026 14:40:11 +0200 Subject: [PATCH 054/111] require CCW winding order MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- rep.md | 1 + 1 file changed, 1 insertion(+) diff --git a/rep.md b/rep.md index 437fece..ba36c53 100644 --- a/rep.md +++ b/rep.md @@ -261,6 +261,7 @@ Procedural texture graphs (noise generation, math nodes, node graphs) are not in ### 3.4 Geometry Constraints * **Triangulation:** Collision meshes must be explicitly triangulated by the author. Visual meshes may use quads or n-gons, but converters targeting glTF 2.0 must triangulate all geometry at export time. +* **Face Orientation:** Meshes must use `orientation = "rightHanded"` (the OpenUSD default), which defines counter-clockwise vertex winding as front-facing. This aligns with glTF 2.0's mandatory CCW front faces. Converters importing from clockwise-oriented sources must rewind vertex indices rather than setting `orientation = "leftHanded"`. Assets must not rely on `doubleSided = true` to mask incorrect winding. * **Manifold topology:** Collision meshes must be watertight (closed, manifold) and free of self-intersections to ensure stable physics and mass derivation. Non-manifold geometry (e.g., open edges) is strictly limited to purely visual meshes. ### 3.5 Instanceable Leaves From ab828cc1e2e75ba52f1e454e19787c0a6a74d671 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Tue, 31 Mar 2026 15:31:55 +0200 Subject: [PATCH 055/111] make more concise MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- rep.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rep.md b/rep.md index ba36c53..a2dec59 100644 --- a/rep.md +++ b/rep.md @@ -261,7 +261,7 @@ Procedural texture graphs (noise generation, math nodes, node graphs) are not in ### 3.4 Geometry Constraints * **Triangulation:** Collision meshes must be explicitly triangulated by the author. Visual meshes may use quads or n-gons, but converters targeting glTF 2.0 must triangulate all geometry at export time. -* **Face Orientation:** Meshes must use `orientation = "rightHanded"` (the OpenUSD default), which defines counter-clockwise vertex winding as front-facing. This aligns with glTF 2.0's mandatory CCW front faces. Converters importing from clockwise-oriented sources must rewind vertex indices rather than setting `orientation = "leftHanded"`. Assets must not rely on `doubleSided = true` to mask incorrect winding. +* **Face Orientation:** Meshes must use `orientation = "rightHanded"` (the OpenUSD default), which defines counter-clockwise vertex winding as front-facing. This aligns with glTF 2.0's mandatory CCW front faces. Assets must not rely on `doubleSided = true` to mask incorrect winding. * **Manifold topology:** Collision meshes must be watertight (closed, manifold) and free of self-intersections to ensure stable physics and mass derivation. Non-manifold geometry (e.g., open edges) is strictly limited to purely visual meshes. ### 3.5 Instanceable Leaves From 867b3ccec1117614dcd02f91aaf3db9bbd6bc39d Mon Sep 17 00:00:00 2001 From: Ayush Ghosh Date: Mon, 6 Apr 2026 22:05:37 -0700 Subject: [PATCH 056/111] Added USD best practices suggestions Signed-off-by: Adam Dabrowski --- rep.md | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/rep.md b/rep.md index a2dec59..8d2b430 100644 --- a/rep.md +++ b/rep.md @@ -86,7 +86,7 @@ As illustrated in Figure 1, assets should be divided into functional layers comp #### 1.2.3 Composition Arcs (LIVRPS Constraints) To guarantee that simulation assets remain self-contained, portable, and predictable across different simulator parsers, asset authors must adhere to the following constraints regarding OpenUSD's LIVRPS composition arcs: * **[L] Local:** Primary authoring of overrides and properties on the asset is fully supported. -* **[I] Inherits & [S] Specializes:** Asset authors should not rely on `Inherits` or `Specializes` arcs for core robot kinematics, physics APIs, or ROS schemas when distributing standalone assets. These arcs create hard dependencies on external class hierarchies; if a simulator's environment lacks the base class definitions, the asset will fail to parse correctly. +* **[I] Inherits & [S] Specializes:** Asset authors should not rely on `Inherits` or `Specializes` arcs that target class definitions outside the asset's own layer stack for core robot kinematics, physics APIs, or ROS schemas when distributing standalone assets. These arcs create hard dependencies on external class hierarchies; if a simulator's environment lacks the base class definitions, the asset will fail to parse correctly. The inherits-instanceable pattern, where the class prim is defined within the same asset, remains valid and is recommended for applying uniform overrides across instances. * **[V] VariantSets:** Permitted and encouraged for asset reusability (see Section 1.2.3). * **[R] References:** Permitted for logical assembly (e.g., composing a robot by referencing an independent `arm.usd` and `base.usd`). * **[P] Payloads (The Payload Pattern):** Heavy data (high-resolution meshes, point clouds, large textures) must be referenced via Payloads rather than standard References. @@ -99,6 +99,12 @@ OpenUSD `VariantSets` are the normative mechanism for asset reusability (e.g., e * **ROS Interface Resolution:** A change in a variant selection may add or remove Prims containing `Ros*API` schemas (e.g., swapping a generic robot head for a sensor-equipped head). Simulators and tooling must only evaluate and spawn ROS interfaces that are active within the currently resolved variant state of the stage. #### 1.2.5 Asset Management +* **Default Prim:** All distributable assets must set `defaultPrim` metadata on the root layer, pointing to the asset's primary entrypoint prim. Without it, referencing `@robot.usd@` without an explicit prim path is undefined behavior and the Payload pattern breaks silently. +* **Asset Identification (`assetInfo`):** All distributable assets must populate the `assetInfo` dictionary on the `defaultPrim` with at minimum: + * `string assetInfo:identifier`: A unique, stable identifier for the asset (e.g., a URI or canonical name). + * `string assetInfo:version`: A version string (e.g., `"1.0.0"`). + * For robotics-specific identifiers that must be carried today (e.g., URDF package origin, original SDF model URI), authors should use a namespaced sub-dictionary (e.g., `assetInfo["ros"]`) following the `UsdMediaAssetPreviewsAPI` precedent. This is a vendor-tier convention positioned for promotion once a broader standard settles. + * *Note: An active AOUSD proposal — [Separation of Concerns for Identifiers in USD (PR #105)](https://github.com/PixarAnimationStudios/OpenUSD-proposals/pull/105) — is evaluating standardized mechanisms for carrying external source identifiers (e.g., PLM part numbers, OPC UA NodeIds, equipment tags) in USD. This REP will adopt the ratified upstream standard once finalized, replacing the interim `assetInfo` convention above.* * **Path Resolution:** Internal references must use relative paths (`./geo/mesh.usdc`). For distributed, highly interoperable assets, all file dependencies should be self-contained and rely exclusively on relative paths. * **ROS packages:** External dependencies to other ROS packages must use the package:// URI scheme, and should be contained in ROS-specific .usd files in the ETL pipeline. Asset authors must be aware that resolving these URIs requires the host simulator or tool to implement a custom OpenUSD ArResolver plugin. Absolute paths and proprietary schemes (e.g., omniverse://) are strictly prohibited in distributed assets. * **Native Composition vs. Custom Prefabs:** The use of custom or vendor-specific string attributes (e.g., `custom string my_sim:prefabPath = "robot.usd"`) to dynamically load, instantiate, or compose assets at runtime is strictly prohibited for interoperable assets. Asset composition must rely purely on native OpenUSD references or payloads. From fcfa9504ae56df3bf79de75deb1ac41bc1dc60ce Mon Sep 17 00:00:00 2001 From: Ayush Ghosh Date: Mon, 6 Apr 2026 22:09:19 -0700 Subject: [PATCH 057/111] Fix formatting Signed-off-by: Adam Dabrowski --- rep.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rep.md b/rep.md index 8d2b430..43c93cc 100644 --- a/rep.md +++ b/rep.md @@ -104,7 +104,7 @@ OpenUSD `VariantSets` are the normative mechanism for asset reusability (e.g., e * `string assetInfo:identifier`: A unique, stable identifier for the asset (e.g., a URI or canonical name). * `string assetInfo:version`: A version string (e.g., `"1.0.0"`). * For robotics-specific identifiers that must be carried today (e.g., URDF package origin, original SDF model URI), authors should use a namespaced sub-dictionary (e.g., `assetInfo["ros"]`) following the `UsdMediaAssetPreviewsAPI` precedent. This is a vendor-tier convention positioned for promotion once a broader standard settles. - * *Note: An active AOUSD proposal — [Separation of Concerns for Identifiers in USD (PR #105)](https://github.com/PixarAnimationStudios/OpenUSD-proposals/pull/105) — is evaluating standardized mechanisms for carrying external source identifiers (e.g., PLM part numbers, OPC UA NodeIds, equipment tags) in USD. This REP will adopt the ratified upstream standard once finalized, replacing the interim `assetInfo` convention above.* + * *Note: An active AOUSD proposal: [Separation of Concerns for Identifiers in USD (PR #105)](https://github.com/PixarAnimationStudios/OpenUSD-proposals/pull/105) is evaluating standardized mechanisms for carrying external source identifiers (e.g., PLM part numbers, OPC UA NodeIds, equipment tags) in USD. This REP will adopt the ratified upstream standard once finalized, replacing the interim `assetInfo` convention above.* * **Path Resolution:** Internal references must use relative paths (`./geo/mesh.usdc`). For distributed, highly interoperable assets, all file dependencies should be self-contained and rely exclusively on relative paths. * **ROS packages:** External dependencies to other ROS packages must use the package:// URI scheme, and should be contained in ROS-specific .usd files in the ETL pipeline. Asset authors must be aware that resolving these URIs requires the host simulator or tool to implement a custom OpenUSD ArResolver plugin. Absolute paths and proprietary schemes (e.g., omniverse://) are strictly prohibited in distributed assets. * **Native Composition vs. Custom Prefabs:** The use of custom or vendor-specific string attributes (e.g., `custom string my_sim:prefabPath = "robot.usd"`) to dynamically load, instantiate, or compose assets at runtime is strictly prohibited for interoperable assets. Asset composition must rely purely on native OpenUSD references or payloads. From da196b6670ff326179edaa46049a21c82e2cde7a Mon Sep 17 00:00:00 2001 From: Ayush Ghosh Date: Tue, 31 Mar 2026 22:49:10 -0700 Subject: [PATCH 058/111] Added sim clock rules Signed-off-by: Adam Dabrowski --- rep.md | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/rep.md b/rep.md index 43c93cc..a853d50 100644 --- a/rep.md +++ b/rep.md @@ -240,6 +240,13 @@ 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 Simulation Clock + +ROS nodes synchronize with simulation time by subscribing to `/clock` and setting `use_sim_time = true`. To ensure all ROS consumers (RViz, Nav2, sensor processors) agree on a common simulation timeline: + +* The clock is a simulator-level concern. Asset USD files must not contain a `RosTopicAPI` prim that publishes to `/clock` as doing so would produce duplicate or conflicting clock sources when multiple assets are composed. +* Compliant simulators must publish simulation time on the absolute `/clock` topic using `rosgraph_msgs/msg/Clock` from the moment simulation begins playing until it is stopped. + --- ## 3. Export and Conversion From b76b7faaf6f47b056f6168f3f81547179d5cf77b Mon Sep 17 00:00:00 2001 From: Ayush Ghosh Date: Wed, 1 Apr 2026 19:20:27 -0700 Subject: [PATCH 059/111] Added some small feedback suggestions Signed-off-by: Adam Dabrowski --- rep.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/rep.md b/rep.md index a853d50..ad94203 100644 --- a/rep.md +++ b/rep.md @@ -244,8 +244,8 @@ OpenUSD cameras natively face the -Z axis, whereas ROS optical frames (REP 103) ROS nodes synchronize with simulation time by subscribing to `/clock` and setting `use_sim_time = true`. To ensure all ROS consumers (RViz, Nav2, sensor processors) agree on a common simulation timeline: -* The clock is a simulator-level concern. Asset USD files must not contain a `RosTopicAPI` prim that publishes to `/clock` as doing so would produce duplicate or conflicting clock sources when multiple assets are composed. -* Compliant simulators must publish simulation time on the absolute `/clock` topic using `rosgraph_msgs/msg/Clock` from the moment simulation begins playing until it is stopped. +* The clock is a simulator-level concern. Asset USD files must not contain any prim that publishes to absolute `/clock` topic, as doing so would produce duplicate or conflicting clock sources when multiple assets are composed. +* Compliant simulators must publish simulation time on the absolute `/clock` topic `rosgraph_msgs/msg/Clock` from the moment simulation begins playing until it is stopped. --- From c51060c48a0cd79649345d0062a25014c53bbb94 Mon Sep 17 00:00:00 2001 From: Ayush Ghosh Date: Thu, 9 Apr 2026 11:41:08 -0700 Subject: [PATCH 060/111] Clarified with prohibited interface section Signed-off-by: Adam Dabrowski --- rep.md | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/rep.md b/rep.md index ad94203..9029f19 100644 --- a/rep.md +++ b/rep.md @@ -4,7 +4,7 @@ | :--- | :--- | | **REP** | XXXX | | **Title** | OpenUSD Conventions for Simulation Asset Interoperability | -| **Authors** | Adam Dabrowski, Mateusz Zak (Robotec.ai) | +| **Authors** | Adam Dabrowski, Mateusz Zak (Robotec.ai), Ayush Ghosh (NVIDIA) | | **Status** | Draft | | **Type** | Standards Track | | **Content-Type** | text/markdown | @@ -240,12 +240,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 Simulation Clock +### 2.9 Prohibited Interfaces -ROS nodes synchronize with simulation time by subscribing to `/clock` and setting `use_sim_time = true`. To ensure all ROS consumers (RViz, Nav2, sensor processors) agree on a common simulation timeline: +Simulator-level interfaces are prohibited in assets to avoid clashes, including: -* The clock is a simulator-level concern. Asset USD files must not contain any prim that publishes to absolute `/clock` topic, as doing so would produce duplicate or conflicting clock sources when multiple assets are composed. -* Compliant simulators must publish simulation time on the absolute `/clock` topic `rosgraph_msgs/msg/Clock` from the moment simulation begins playing until it is stopped. +* `/clock` topic (`rosgraph_msgs/msg/Clock` interface) for simulation time. +* Any interfaces included in the `simulation_interfaces` package (e.g. spawning, simulation control). --- From 5cd1d2f98962f2eed5e96697a00c33f5664c20ac Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Fri, 10 Apr 2026 15:30:10 +0200 Subject: [PATCH 061/111] Remove hierarchy mandate Following discussion on #22 Resolves #22 Signed-off-by: Adam Dabrowski --- rep.md | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/rep.md b/rep.md index 9029f19..aa2ca75 100644 --- a/rep.md +++ b/rep.md @@ -116,9 +116,7 @@ OpenUSD's native instancing mechanisms are designed for repetitive visual and st * **Runtime Delegation:** Simulators supporting massive parallelism are expected to handle environment replication natively at runtime via their own APIs. Authors must not bake thousands of physics-enabled clones into the source file. ### 1.3 Physics -* **Rigid Body Hierarchy:** Assets should utilize Logical Nesting to represent kinematic chains (e.g., `Forearm` is a child of `UpperArm`). This preserves the Scene Graph for TF tree generation and ensures compatibility with parsers expecting URDF/SDF-like topologies (e.g., MuJoCo). - * Simulators that require flat hierarchies are responsible for flattening the graph at import time. The asset itself must remain logically nested. -* **Joint Placement:** While `UsdPhysicsJoint` prims rely on relational targeting (`body0` and `body1`) rather than hierarchy, asset authors should place the Joint prim as a sibling adjacent to the child link it connects, within the scope of the parent link. This ensures self-contained modularity. +* **Joint Placement:** Asset authors should place the joint prim as a sibling adjacent to the child link it connects, within the scope of the parent link, to ensure self-contained modularity. Note that `UsdPhysicsJoint` prims rely on relational targeting (`body0` and `body1`) rather than hierarchy, which means parsers must reconstruct the kinematic tree exclusively from these relationships. * **Joint Limits:** Non-continuous joints (e.g., revolute, prismatic) must author explicit `physics:lowerLimit` and `physics:upperLimit` attributes. * **Articulation Roots:** A composed simulation stage must contain at most one `UsdPhysicsArticulationRootAPI` per connected kinematic tree. * Assets (e.g., a modular gripper) should be self-contained with an articulation root for standalone use. From 704eedf58962c0f646a194b7f12119c3449f7ecf Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Micha=C5=82=20Pe=C5=82ka?= Date: Mon, 30 Mar 2026 15:20:02 +0200 Subject: [PATCH 062/111] Added 4th section regarding robot control. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Michał Pełka Signed-off-by: Adam Dabrowski --- rep.md | 103 ++++++++++++++++++++++++++++++++++++++++++++++++++++++++- 1 file changed, 102 insertions(+), 1 deletion(-) diff --git a/rep.md b/rep.md index aa2ca75..2c60153 100644 --- a/rep.md +++ b/rep.md @@ -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 @@ -238,12 +239,20 @@ 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. +<<<<<<< HEAD ### 2.9 Prohibited Interfaces Simulator-level interfaces are prohibited in assets to avoid clashes, including: * `/clock` topic (`rosgraph_msgs/msg/Clock` interface) for simulation time. * Any interfaces included in the `simulation_interfaces` package (e.g. spawning, simulation control). +======= +### 2.9 Joint Identification and Interoperability (ROS2JointAPI) + +Applies to prims that possess a `PhysicsJointAPI` and are part of a kinematic chain of the robot. +Used to identify and map joints between an imported scene and ROS-native concepts such as robot descriptions. This API enables one-to-one mapping between joints controlled by the ROS 2 control framework. +* `string ros2:joint:name`: The name of the joint (without namespace). +>>>>>>> 032622a (Added 4th section regarding robot control.) --- @@ -299,6 +308,98 @@ 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 ``, MJCF ``). Obsolete approaches such as injecting legacy `` 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 and their interactions. +This approach is often used for low-level control and real-time feedback, allowing for more precise manipulation of the robot's movements and behaviors. In this context, the simulator exposes +a set of endpoints for controlling and monitoring the individual components of the robot and their control and state interfaces. + +In application level simulation, the simulator simulates the robot as a whole, including its physical properties, kinematics, and dynamics. +This approach is often used for high-level planning and interaction with the environment. +It simplifies the process of simulating multi-robot scenarios. + +### 4.1 Control Interfaces + +The control interface uses ROS2JointAPI for controllable joint identification and the interface to be used with the control framework. +The shape and form of the interface that the simulator exposes to the control framework is not the scope of this REP and is simulator specific. + +### 4.2 Application Simulation +ROS2ControlAPI allows instantiating robot controllers directly in the simulated scene. +It must reference one or more prims that have [ROS2TopicAPI](#24-topic-interface-ros2topicapi), [ROS2ServiceAPI](#25-service-interface-ros2serviceapi) or [ROS2ActionAPI](#26-action-interface-ros2actionapi). +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::CustomROS2RigidBodyTwistControllerAPI` which will include as built-in `ROS2ControlAPI` and reference prims: +- `ROS2TopicAPI` 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 ROS2ControlAPI have at least one of the following API schemas applied: `ROS2TopicAPI`, `ROS2ServiceAPI` or `ROS2ActionAPI`. +### 4.2.1 Built-in Controllers + +The following schemas are built-in controller schemas that include +`ROS2ControlAPI` as a built-in via `prepend apiSchemas`. +Simulators may implement these schemas to provide a standardized +control interface for common use cases. + +#### 4.2.1.1 ROS2RigidBodyTwistControllerAPI + +Controls a rigid body by subscribing to a `geometry_msgs/Twist` message +and applying the commanded linear and angular velocities directly to the +physics engine. + +- `rel ros2:rigid_body_twist:cmd_vel`: Reference to a prim with `ROS2TopicAPI` + for subscribing to twist control messages. +- `rel ros2:rigid_body_twist:body`: Reference to a prim with + `UsdPhysicsRigidBodyAPI` for applying velocities. + +- `double ros2:rigid_body_twist:cmd_vel_timeout`: Timeout in seconds after + which the command is considered stale. Default: `0.5`. +- `double ros2:rigid_body_twist:linear:x:max_velocity`: Maximum linear velocity in m/s. +- `double ros2:rigid_body_twist:linear:x:max_acceleration`: Maximum linear acceleration in m/s². +- `double ros2:rigid_body_twist:angular:z:max_velocity`: Maximum angular velocity in rad/s. +- `double ros2:rigid_body_twist:angular:z:max_acceleration`: Maximum angular acceleration in rad/s². + +#### 4.2.1.2 ROS2DiffDriveControllerAPI + +Controls a differential drive robot by subscribing to a +`geometry_msgs/Twist` message and converting the commanded linear +and angular velocities into individual wheel velocities applied +to the simulator joints. + +- `rel ros2:diff_drive:cmd_vel`: Reference to prim with `ROS2TopicAPI` for subscribing to velocity commands. +- `rel ros2:diff_drive:odom`: Reference to prim with `ROS2TopicAPI` for publishing odometry data. +- `rel[] ros2:diff_drive:left_wheels`: References to prims with `UsdPhysicsDriveAPI` representing left wheel joints. +- `rel[] ros2:diff_drive:right_wheels`: References to prims with `UsdPhysicsDriveAPI` representing right wheel joints. +- `double ros2:diff_drive:wheel_separation`: Distance between left and right wheels in meters. +- `double ros2:diff_drive:wheel_radius`: Radius of the wheels in meters. +- `double ros2:diff_drive:cmd_vel_timeout`: Timeout in seconds after which the command is considered stale. Default: `0.5`. +- `double ros2:diff_drive:linear:x:max_velocity`: Maximum linear velocity in m/s. +- `double ros2:diff_drive:linear:x:max_acceleration`: Maximum linear acceleration in m/s². +- `double ros2:diff_drive:angular:z:max_velocity`: Maximum angular velocity in rad/s. +- `double ros2:diff_drive:angular:z:max_acceleration`: Maximum angular acceleration in rad/s². + +#### 4.2.1.3 ROS2JointTrajectoryControllerAPI + +Executes a joint trajectory by accepting a +`control_msgs/FollowJointTrajectory` action goal and commanding +the simulator to follow the specified trajectory. + +**Relationships (Required):** +- `rel ros2:joint_trajectory:server`: Reference to a prim with `ROS2ActionAPI` + for receiving trajectory action goals. +- `rel[] ros2:joint_trajectory:joints`: References to prims with + `PhysicsJointAPI` and `ROS2JointAPI` representing the joints + to be controlled. + +**Core Attributes (Optional):** +- `double ros2:joint_trajectory:action_monitor_rate`: Frequency in Hz for + monitoring trajectory execution progress. +- `double ros2:joint_trajectory:stopped_velocity_tolerance`: Velocity tolerance + at the end of the trajectory that indicates the controlled system has stopped. +- `double ros2:joint_trajectory:goal_time`: Maximum time allowed to reach + the trajectory goal. + + ## Tools ### Schema Definition From 4713384a111a46a892d52ab78bd821634b783cc1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Micha=C5=82=20Pe=C5=82ka?= Date: Fri, 3 Apr 2026 14:34:26 +0200 Subject: [PATCH 063/111] =?UTF-8?q?Added=20`ros2:joint:name`=20custom=20at?= =?UTF-8?q?tribute=20instead=20of=20ROS2JointAPI=20schema.=20Added=20`ROS2?= =?UTF-8?q?JointStateBroadcasterAPI`.=20Created=20differentiation=20betwee?= =?UTF-8?q?n=20`ROS2IntegratedControlAPI`=20and=20`Ros2IntegratedControlAP?= =?UTF-8?q?I`.=20Signed-off-by:=20Micha=C5=82=20Pe=C5=82ka=20?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Adam Dabrowski --- rep.md | 98 ++++++++----- schema/schema.usda | 356 +++++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 418 insertions(+), 36 deletions(-) diff --git a/rep.md b/rep.md index 2c60153..0d48778 100644 --- a/rep.md +++ b/rep.md @@ -181,7 +181,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. @@ -239,22 +239,23 @@ 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. -<<<<<<< HEAD + + ### 2.9 Prohibited Interfaces Simulator-level interfaces are prohibited in assets to avoid clashes, including: * `/clock` topic (`rosgraph_msgs/msg/Clock` interface) for simulation time. * Any interfaces included in the `simulation_interfaces` package (e.g. spawning, simulation control). -======= -### 2.9 Joint Identification and Interoperability (ROS2JointAPI) -Applies to prims that possess a `PhysicsJointAPI` and are part of a kinematic chain of the robot. -Used to identify and map joints between an imported scene and ROS-native concepts such as robot descriptions. This API enables one-to-one mapping between joints controlled by the ROS 2 control framework. -* `string ros2:joint:name`: The name of the joint (without namespace). ->>>>>>> 032622a (Added 4th section regarding robot control.) +======= +### 2.10 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 `ros2: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 ``). +If this property is missing, simulators must fall back to using the prim name. +>>>>>>> 84b460b (Added `ros2:joint:name` custom attribute instead of ROS2JointAPI schema.) ## 3. Export and Conversion @@ -312,21 +313,28 @@ OpenUSD and robotics XML formats (URDF, SDF, MJCF) are fundamentally mismatched 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 and their interactions. -This approach is often used for low-level control and real-time feedback, allowing for more precise manipulation of the robot's movements and behaviors. In this context, the simulator exposes -a set of endpoints for controlling and monitoring the individual components of the robot and their control and state interfaces. +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 often used for high-level planning and interaction with the environment. -It simplifies the process of simulating multi-robot scenarios. +This approach is often used for high-level planning and interaction with the environment. +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 Control Interfaces +### 4.1 External Control Interfaces -The control interface uses ROS2JointAPI for controllable joint identification and the interface to be used with the control framework. -The shape and form of the interface that the simulator exposes to the control framework is not the scope of this REP and is simulator specific. +The ROS 2 external control `ROS2ExternalControlAPI` 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 Application Simulation -ROS2ControlAPI allows instantiating robot controllers directly in the simulated scene. +### 4.2 Integrated Controller Simulation + +`ROS2IntegratedControlAPI` allows instantiating robot controllers directly in the simulated scene. It must reference one or more prims that have [ROS2TopicAPI](#24-topic-interface-ros2topicapi), [ROS2ServiceAPI](#25-service-interface-ros2serviceapi) or [ROS2ActionAPI](#26-action-interface-ros2actionapi). 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::CustomROS2RigidBodyTwistControllerAPI` which will include as built-in `ROS2ControlAPI` and reference prims: @@ -334,20 +342,28 @@ Example can be `simulatorXYZ::CustomROS2RigidBodyTwistControllerAPI` which will - `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 ROS2ControlAPI have at least one of the following API schemas applied: `ROS2TopicAPI`, `ROS2ServiceAPI` or `ROS2ActionAPI`. + ### 4.2.1 Built-in Controllers The following schemas are built-in controller schemas that include `ROS2ControlAPI` 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 ROS2RigidBodyTwistControllerAPI -Controls a rigid body by subscribing to a `geometry_msgs/Twist` message -and applying the commanded linear and angular velocities directly to the -physics engine. +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 ros2:rigid_body_twist:cmd_vel`: Reference to a prim with `ROS2TopicAPI` +- `rel ros2:rigid_body_twist:subscriber`: Reference to a prim with `ROS2TopicAPI` for subscribing to twist control messages. - `rel ros2:rigid_body_twist:body`: Reference to a prim with `UsdPhysicsRigidBodyAPI` for applying velocities. @@ -361,12 +377,15 @@ physics engine. #### 4.2.1.2 ROS2DiffDriveControllerAPI -Controls a differential drive robot by subscribing to a +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. +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 ros2:diff_drive:cmd_vel`: Reference to prim with `ROS2TopicAPI` for subscribing to velocity commands. +- `rel ros2:diff_drive:subscriber`: Reference to prim with `ROS2TopicAPI` for subscribing to velocity commands. - `rel ros2:diff_drive:odom`: Reference to prim with `ROS2TopicAPI` for publishing odometry data. - `rel[] ros2:diff_drive:left_wheels`: References to prims with `UsdPhysicsDriveAPI` representing left wheel joints. - `rel[] ros2:diff_drive:right_wheels`: References to prims with `UsdPhysicsDriveAPI` representing right wheel joints. @@ -380,25 +399,32 @@ to the simulator joints. #### 4.2.1.3 ROS2JointTrajectoryControllerAPI -Executes a joint trajectory by accepting a -`control_msgs/FollowJointTrajectory` action goal and commanding +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 `ros2:joint:name` property of the joint prims and +use it for mapping trajectory points to joints in the simulator. -**Relationships (Required):** - `rel ros2:joint_trajectory:server`: Reference to a prim with `ROS2ActionAPI` for receiving trajectory action goals. -- `rel[] ros2:joint_trajectory:joints`: References to prims with - `PhysicsJointAPI` and `ROS2JointAPI` representing the joints - to be controlled. - -**Core Attributes (Optional):** +- `rel[] ros2:joint_trajectory:command_joints`: References to prims with `UsdPhysicsJointAPI`. - `double ros2:joint_trajectory:action_monitor_rate`: Frequency in Hz for monitoring trajectory execution progress. - `double ros2:joint_trajectory:stopped_velocity_tolerance`: Velocity tolerance at the end of the trajectory that indicates the controlled system has stopped. -- `double ros2:joint_trajectory:goal_time`: Maximum time allowed to reach - the trajectory goal. +- `double ros2:joint_trajectory:timeout`: Maximum time allowed to reach the trajectory goal. + +#### 4.2.1.4 ROS2JointStateBroadcasterAPI + +Reads joint states from the simulator and publishes them as `sensor_msgs/JointState` messages to a ROS2 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 `ros2:joint:name` +property of the joint prims and use it for mapping trajectory points to joints in the simulator. +- `rel ros2:joint_state_broadcaster:publisher`: Reference to a prim with `ROS2TopicAPI` for publishing joint state data. +- `rel[] ros2:joint_state_broadcaster:joints`: References to prims with `UsdPhysicsJointAPI` representing the joints whose states are to be broadcast. +- `double ros2:joint_state_broadcaster:publish_rate`: Frequency in Hz at which joint states are published. +- `string ros2:joint_state_broadcaster:frame_id`: The TF frame ID to be used in the published JointState messages. ## Tools diff --git a/schema/schema.usda b/schema/schema.usda index 2641b6d..3ffd881 100644 --- a/schema/schema.usda +++ b/schema/schema.usda @@ -342,3 +342,359 @@ class "Ros2FrameAPI" ( USD TimeSamples), the simulator broadcasts to /tf.""" ) } + +# ====================================================================== +# Section 4 - Robot Control +# +# Two approaches to simulating a robotic system are defined: +# +# Control-level simulation (Section 4.1): +# The simulator exposes joint state and command interfaces to an +# external control algorithm. The interface shape is simulator- +# specific (e.g. ros2_control hardware_interface, IPC, HIL). +# Prims are marked with Ros2ExternalControlAPI as a built-in. +# +# Application-level (integrated) simulation (Section 4.2): +# The controller runs inside the simulator and is configured via +# prim parameters and ROS communication. Prims are marked with +# Ros2IntegratedControlAPI as a built-in and reference topic, +# service, or action interface prims. +# ====================================================================== + +# ====================================================================== +# Section 4.1 - Ros2ExternalControlAPI +# ====================================================================== + +class "Ros2ExternalControlAPI" ( + inherits = + customData = { + token apiSchemaType = "singleApply" + string className = "ExternalControlAPI" + } + doc = """Base schema for exposing robot control interfaces to external control algorithms. + + Applied (via 'prepend apiSchemas') by simulator-specific schemas to + identify prims whose joint state and command interfaces should be + exposed to an external control entity (e.g. a ros2_control + hardware_interface plugin, an inter-process controller, or a + hardware-in-the-loop connection). + """ +) +{ +} + +# ====================================================================== +# Section 4.2 - Ros2IntegratedControlAPI +# ====================================================================== + +class "Ros2IntegratedControlAPI" ( + inherits = + customData = { + token apiSchemaType = "singleApply" + string className = "IntegratedControlAPI" + } + doc = """Base schema for integrated (application-level) robot controllers. + + Included as a built-in via 'prepend apiSchemas' by simulator-specific + or standardized controller schemas that run the controller logic + inside the simulator. All prims referenced by a controller that + inherits this schema must have at least one of Ros2TopicAPI, + Ros2ServiceAPI, or Ros2ActionAPI applied. USD does not enforce this + constraint at the schema level; simulators are responsible for + runtime validation. + """ +) +{ +} + +# ====================================================================== +# Section 4.2.1.1 - Ros2RigidBodyTwistControllerAPI +# ====================================================================== + +class "Ros2RigidBodyTwistControllerAPI" ( + inherits = + prepend apiSchemas = ["Ros2IntegratedControlAPI"] + customData = { + token apiSchemaType = "singleApply" + string className = "RigidBodyTwistControllerAPI" + } + doc = """Controls a rigid body via geometry_msgs/Twist messages. + + Subscribes to a Twist topic and applies the commanded linear and + angular velocities directly to a rigid body in the physics engine, + with optional velocity and acceleration limits. Implementation should + follow logic similar to the diff_drive_controller in ros2_controllers. + """ +) +{ + rel ros2:rigid_body_twist:subscriber ( + customData = { + string apiName = "subscriber" + } + doc = """Reference to a prim with Ros2TopicAPI configured as a + subscription for geometry_msgs/Twist control messages.""" + ) + + rel ros2:rigid_body_twist:body ( + customData = { + string apiName = "body" + } + doc = """Reference to a prim with UsdPhysicsRigidBodyAPI to which + the commanded velocities are applied.""" + ) + + uniform double ros2:rigid_body_twist:cmd_vel_timeout = 0.5 ( + customData = { + string apiName = "cmdVelTimeout" + } + doc = """Timeout in seconds after which a velocity command is + considered stale and the body velocity is zeroed.""" + ) + + uniform double ros2:rigid_body_twist:linear:x:max_velocity ( + customData = { + string apiName = "linearXMaxVelocity" + } + doc = """Maximum linear velocity along the X axis in m/s.""" + ) + + uniform double ros2:rigid_body_twist:linear:x:max_acceleration ( + customData = { + string apiName = "linearXMaxAcceleration" + } + doc = """Maximum linear acceleration along the X axis in m/s².""" + ) + + uniform double ros2:rigid_body_twist:angular:z:max_velocity ( + customData = { + string apiName = "angularZMaxVelocity" + } + doc = """Maximum angular velocity around the Z axis in rad/s.""" + ) + + uniform double ros2:rigid_body_twist:angular:z:max_acceleration ( + customData = { + string apiName = "angularZMaxAcceleration" + } + doc = """Maximum angular acceleration around the Z axis in rad/s².""" + ) +} + +# ====================================================================== +# Section 4.2.1.2 - Ros2DiffDriveControllerAPI +# ====================================================================== + +class "Ros2DiffDriveControllerAPI" ( + inherits = + prepend apiSchemas = ["Ros2IntegratedControlAPI"] + customData = { + token apiSchemaType = "singleApply" + string className = "DiffDriveControllerAPI" + } + doc = """Controls a differential drive robot via geometry_msgs/Twist messages. + + Subscribes to a Twist topic, converts commanded linear and angular + velocities into individual wheel velocities, and applies them to + wheel joint prims with UsdPhysicsDriveAPI. Publishes odometry data + as nav_msgs/Odometry. Implementation should follow logic similar to + the diff_drive_controller in ros2_controllers. + """ +) +{ + rel ros2:diff_drive:subscriber ( + customData = { + string apiName = "subscriber" + } + doc = """Reference to a prim with Ros2TopicAPI configured as a + subscription for geometry_msgs/Twist velocity commands.""" + ) + + rel ros2:diff_drive:odom ( + customData = { + string apiName = "odom" + } + doc = """Reference to a prim with Ros2TopicAPI configured as a + publisher for nav_msgs/Odometry data.""" + ) + + rel ros2:diff_drive:left_wheels ( + customData = { + string apiName = "leftWheels" + } + doc = """References to prims with UsdPhysicsDriveAPI representing + the left wheel joints.""" + ) + + rel ros2:diff_drive:right_wheels ( + customData = { + string apiName = "rightWheels" + } + doc = """References to prims with UsdPhysicsDriveAPI representing + the right wheel joints.""" + ) + + uniform double ros2:diff_drive:wheel_separation ( + customData = { + string apiName = "wheelSeparation" + } + doc = """Distance between the left and right wheel contact points + in meters.""" + ) + + uniform double ros2:diff_drive:wheel_radius ( + customData = { + string apiName = "wheelRadius" + } + doc = """Radius of the wheels in meters.""" + ) + + uniform double ros2:diff_drive:cmd_vel_timeout = 0.5 ( + customData = { + string apiName = "cmdVelTimeout" + } + doc = """Timeout in seconds after which a velocity command is + considered stale and wheel velocities are zeroed.""" + ) + + uniform double ros2:diff_drive:linear:x:max_velocity ( + customData = { + string apiName = "linearXMaxVelocity" + } + doc = """Maximum linear velocity along the X axis in m/s.""" + ) + + uniform double ros2:diff_drive:linear:x:max_acceleration ( + customData = { + string apiName = "linearXMaxAcceleration" + } + doc = """Maximum linear acceleration along the X axis in m/s².""" + ) + + uniform double ros2:diff_drive:angular:z:max_velocity ( + customData = { + string apiName = "angularZMaxVelocity" + } + doc = """Maximum angular velocity around the Z axis in rad/s.""" + ) + + uniform double ros2:diff_drive:angular:z:max_acceleration ( + customData = { + string apiName = "angularZMaxAcceleration" + } + doc = """Maximum angular acceleration around the Z axis in rad/s².""" + ) +} + +# ====================================================================== +# Section 4.2.1.3 - Ros2JointTrajectoryControllerAPI +# ====================================================================== + +class "Ros2JointTrajectoryControllerAPI" ( + inherits = + prepend apiSchemas = ["Ros2IntegratedControlAPI"] + customData = { + token apiSchemaType = "singleApply" + string className = "JointTrajectoryControllerAPI" + } + doc = """Executes joint trajectories via control_msgs/FollowJointTrajectory actions. + + Accepts action goals and commands the simulator to follow the + specified joint trajectory. Implementation should follow logic + similar to the joint_trajectory_controller in ros2_controllers. + """ +) +{ + rel ros2:joint_trajectory:server ( + customData = { + string apiName = "server" + } + doc = """Reference to a prim with Ros2ActionAPI configured as a + server for control_msgs/FollowJointTrajectory action goals.""" + ) + + rel ros2:joint_trajectory:command_joints ( + customData = { + string apiName = "commandJoints" + } + doc = """References to prims with UsdPhysicsJointAPI representing + the joints to be commanded along the trajectory. Simulators must + use the ros2:joint:name custom property for joint name mapping, + falling back to the prim name if absent.""" + ) + + uniform double ros2:joint_trajectory:action_monitor_rate ( + customData = { + string apiName = "actionMonitorRate" + } + doc = """Frequency in Hz at which trajectory execution progress + is monitored.""" + ) + + uniform double ros2:joint_trajectory:stopped_velocity_tolerance ( + customData = { + string apiName = "stoppedVelocityTolerance" + } + doc = """Velocity tolerance at the end of the trajectory below + which the controlled system is considered stopped.""" + ) + + uniform double ros2:joint_trajectory:timeout ( + customData = { + string apiName = "timeout" + } + doc = """Maximum time in seconds allowed to reach the trajectory + goal before the action is aborted.""" + ) +} + +# ====================================================================== +# Section 4.2.1.4 - Ros2JointStateBroadcasterAPI +# ====================================================================== + +class "Ros2JointStateBroadcasterAPI" ( + inherits = + prepend apiSchemas = ["Ros2IntegratedControlAPI"] + customData = { + token apiSchemaType = "singleApply" + string className = "JointStateBroadcasterAPI" + } + doc = """Reads joint states and publishes them as sensor_msgs/JointState messages. + + Implementation should follow logic similar to the + joint_state_broadcaster in ros2_controllers. + """ +) +{ + rel ros2:joint_state_broadcaster:publisher ( + customData = { + string apiName = "publisher" + } + doc = """Reference to a prim with Ros2TopicAPI configured as a + publisher for sensor_msgs/JointState messages.""" + ) + + rel ros2:joint_state_broadcaster:joints ( + customData = { + string apiName = "joints" + } + doc = """References to prims with UsdPhysicsJointAPI representing + the joints whose states are to be broadcast. Simulators must use + the ros2:joint:name custom property for joint name mapping, + falling back to the prim name if absent.""" + ) + + uniform double ros2:joint_state_broadcaster:publish_rate ( + customData = { + string apiName = "publishRate" + } + doc = """Frequency in Hz at which joint states are published.""" + ) + + uniform string ros2:joint_state_broadcaster:frame_id ( + customData = { + string apiName = "frameId" + } + doc = """The TF frame_id to be used in the published JointState + messages.""" + ) +} From 8bd9f1cef00314f89d9fe5bf5d27d5448a41f335 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Micha=C5=82=20Pe=C5=82ka?= Date: Fri, 3 Apr 2026 16:41:04 +0200 Subject: [PATCH 064/111] Applied ROS 2 is ROS to rep.md MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Michał Pełka Signed-off-by: Adam Dabrowski --- rep.md | 84 +++++++++++++++++++++++++++++----------------------------- 1 file changed, 42 insertions(+), 42 deletions(-) diff --git a/rep.md b/rep.md index 0d48778..931937e 100644 --- a/rep.md +++ b/rep.md @@ -252,7 +252,7 @@ Simulator-level interfaces are prohibited in assets to avoid clashes, including: ### 2.10 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 `ros2:joint:name` must be applied to all Prims bearing built-in`UsdPhysicsJoint` schema. +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 ``). If this property is missing, simulators must fall back to using the prim name. >>>>>>> 84b460b (Added `ros2:joint:name` custom attribute instead of ROS2JointAPI schema.) @@ -327,26 +327,26 @@ In this approach the controller is integrated in the simulator codebase and mana ### 4.1 External Control Interfaces -The ROS 2 external control `ROS2ExternalControlAPI` is a schema for exposing robot control interfaces to external control algorithms. +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 -`ROS2IntegratedControlAPI` allows instantiating robot controllers directly in the simulated scene. -It must reference one or more prims that have [ROS2TopicAPI](#24-topic-interface-ros2topicapi), [ROS2ServiceAPI](#25-service-interface-ros2serviceapi) or [ROS2ActionAPI](#26-action-interface-ros2actionapi). +`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::CustomROS2RigidBodyTwistControllerAPI` which will include as built-in `ROS2ControlAPI` and reference prims: -- `ROS2TopicAPI` for subscription of control message. +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 ROS2ControlAPI have at least one of the following API schemas applied: `ROS2TopicAPI`, `ROS2ServiceAPI` or `ROS2ActionAPI`. +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 -`ROS2ControlAPI` as a built-in via `prepend apiSchemas`. +`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. @@ -356,26 +356,26 @@ Simulators may choose to implement additional controllers as needed for their sp application level simulation. The implementation should allow performing multi-robot simulation and control by leveraging the namespaces. -#### 4.2.1.1 ROS2RigidBodyTwistControllerAPI +#### 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 ros2:rigid_body_twist:subscriber`: Reference to a prim with `ROS2TopicAPI` +- `rel ros:rigid_body_twist:subscriber`: Reference to a prim with `ROSTopicAPI` for subscribing to twist control messages. -- `rel ros2:rigid_body_twist:body`: Reference to a prim with +- `rel ros:rigid_body_twist:body`: Reference to a prim with `UsdPhysicsRigidBodyAPI` for applying velocities. -- `double ros2:rigid_body_twist:cmd_vel_timeout`: Timeout in seconds after +- `double ros:rigid_body_twist:cmd_vel_timeout`: Timeout in seconds after which the command is considered stale. Default: `0.5`. -- `double ros2:rigid_body_twist:linear:x:max_velocity`: Maximum linear velocity in m/s. -- `double ros2:rigid_body_twist:linear:x:max_acceleration`: Maximum linear acceleration in m/s². -- `double ros2:rigid_body_twist:angular:z:max_velocity`: Maximum angular velocity in rad/s. -- `double ros2:rigid_body_twist:angular:z:max_acceleration`: Maximum angular acceleration in rad/s². +- `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 ROS2DiffDriveControllerAPI +#### 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 @@ -385,46 +385,46 @@ The computed velocities should be applied to prims with `UsdPhysicsDriveAPI` (pa 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 ros2:diff_drive:subscriber`: Reference to prim with `ROS2TopicAPI` for subscribing to velocity commands. -- `rel ros2:diff_drive:odom`: Reference to prim with `ROS2TopicAPI` for publishing odometry data. -- `rel[] ros2:diff_drive:left_wheels`: References to prims with `UsdPhysicsDriveAPI` representing left wheel joints. -- `rel[] ros2:diff_drive:right_wheels`: References to prims with `UsdPhysicsDriveAPI` representing right wheel joints. -- `double ros2:diff_drive:wheel_separation`: Distance between left and right wheels in meters. -- `double ros2:diff_drive:wheel_radius`: Radius of the wheels in meters. -- `double ros2:diff_drive:cmd_vel_timeout`: Timeout in seconds after which the command is considered stale. Default: `0.5`. -- `double ros2:diff_drive:linear:x:max_velocity`: Maximum linear velocity in m/s. -- `double ros2:diff_drive:linear:x:max_acceleration`: Maximum linear acceleration in m/s². -- `double ros2:diff_drive:angular:z:max_velocity`: Maximum angular velocity in rad/s. -- `double ros2:diff_drive:angular:z:max_acceleration`: Maximum angular acceleration in rad/s². +- `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 ROS2JointTrajectoryControllerAPI +#### 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 `ros2:joint:name` property of the joint prims and +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 ros2:joint_trajectory:server`: Reference to a prim with `ROS2ActionAPI` +- `rel ros:joint_trajectory:server`: Reference to a prim with `ROSActionAPI` for receiving trajectory action goals. -- `rel[] ros2:joint_trajectory:command_joints`: References to prims with `UsdPhysicsJointAPI`. -- `double ros2:joint_trajectory:action_monitor_rate`: Frequency in Hz for +- `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 ros2:joint_trajectory:stopped_velocity_tolerance`: Velocity tolerance +- `double ros:joint_trajectory:stopped_velocity_tolerance`: Velocity tolerance at the end of the trajectory that indicates the controlled system has stopped. -- `double ros2:joint_trajectory:timeout`: Maximum time allowed to reach the trajectory goal. +- `double ros:joint_trajectory:timeout`: Maximum time allowed to reach the trajectory goal. -#### 4.2.1.4 ROS2JointStateBroadcasterAPI +#### 4.2.1.4 ROSJointStateBroadcasterAPI -Reads joint states from the simulator and publishes them as `sensor_msgs/JointState` messages to a ROS2 topic. +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 `ros2:joint:name` +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 ros2:joint_state_broadcaster:publisher`: Reference to a prim with `ROS2TopicAPI` for publishing joint state data. -- `rel[] ros2:joint_state_broadcaster:joints`: References to prims with `UsdPhysicsJointAPI` representing the joints whose states are to be broadcast. -- `double ros2:joint_state_broadcaster:publish_rate`: Frequency in Hz at which joint states are published. -- `string ros2:joint_state_broadcaster:frame_id`: The TF frame ID to be used in the published JointState messages. +- `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 From 2bafd490bb72d4149537ba6c445847f38120be53 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Micha=C5=82=20Pe=C5=82ka?= Date: Fri, 3 Apr 2026 16:41:04 +0200 Subject: [PATCH 065/111] Applied ROS 2 is ROS to rep.md MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Michał Pełka Signed-off-by: Adam Dabrowski --- rep.md | 1 - 1 file changed, 1 deletion(-) diff --git a/rep.md b/rep.md index 931937e..98ea582 100644 --- a/rep.md +++ b/rep.md @@ -321,7 +321,6 @@ The REP-XXXX does not propose shape of the API and interface, and simulators are 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 often used for high-level planning and interaction with the environment. 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. From a59374c431d952dc8844a6744f7f736ff4261eb2 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Micha=C5=82=20Pe=C5=82ka?= Date: Fri, 3 Apr 2026 17:25:37 +0200 Subject: [PATCH 066/111] ROS 2 is ROS in schema.usda MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Michał Pełka Signed-off-by: Adam Dabrowski --- schema/schema.usda | 188 ++++++++++++++++++++++----------------------- 1 file changed, 94 insertions(+), 94 deletions(-) diff --git a/schema/schema.usda b/schema/schema.usda index 3ffd881..5978ace 100644 --- a/schema/schema.usda +++ b/schema/schema.usda @@ -1,7 +1,7 @@ #usda 1.0 ( - "ROS 2 Integration Schemas for OpenUSD Simulation Asset Interoperability." - " Defines declarative, engine-agnostic API schemas for ROS 2 interfaces" + "ROS Integration Schemas for OpenUSD Simulation Asset Interoperability." + " Defines declarative, engine-agnostic API schemas for ROS interfaces" " as specified in REP-XXXX, Section 2." subLayers = [ @usd/schema.usda@ @@ -10,9 +10,9 @@ over "GLOBAL" ( customData = { - string libraryName = "usdRos2" - string libraryPath = "usdRos2" - string libraryPrefix = "UsdRos2" + string libraryName = "usdRos" + string libraryPath = "usdRos" + string libraryPrefix = "UsdRos" dictionary libraryTokens = { # --- Role tokens (shared by Topic, Service, Action) --- dictionary publisher = { @@ -55,7 +55,7 @@ over "GLOBAL" ( # --- Frame tokens --- dictionary world = { - string doc = """Default parent frame for the top-most Ros2ContextAPI.""" + string doc = """Default parent frame for the top-most RosContextAPI.""" } } } @@ -64,10 +64,10 @@ over "GLOBAL" ( } # ====================================================================== -# Section 2.1 - Ros2ContextAPI +# Section 2.1 - RosContextAPI # ====================================================================== -class "Ros2ContextAPI" ( +class "RosContextAPI" ( inherits = customData = { token apiSchemaType = "singleApply" @@ -83,7 +83,7 @@ class "Ros2ContextAPI" ( """ ) { - uniform string ros2:context:namespace ( + uniform string ros:context:namespace ( customData = { string apiName = "namespace" } @@ -91,7 +91,7 @@ class "Ros2ContextAPI" ( The namespace is additive in the asset hierarchy.""" ) - uniform int ros2:context:domain_id ( + uniform int ros:context:domain_id ( customData = { string apiName = "domainId" } @@ -99,7 +99,7 @@ class "Ros2ContextAPI" ( descending from this context.""" ) - uniform string ros2:context:parent_frame = "world" ( + uniform string ros:context:parent_frame = "world" ( customData = { string apiName = "parentFrame" } @@ -111,10 +111,10 @@ class "Ros2ContextAPI" ( } # ====================================================================== -# Section 2.4 - Ros2TopicAPI +# Section 2.4 - RosTopicAPI # ====================================================================== -class "Ros2TopicAPI" ( +class "RosTopicAPI" ( inherits = customData = { token apiSchemaType = "singleApply" @@ -123,7 +123,7 @@ class "Ros2TopicAPI" ( doc = """Applied to prims exchanging streaming ROS 2 data. Simulators spawn the corresponding publisher or subscription at - runtime. Robot-wide interfaces go on or beneath the Ros2ContextAPI + runtime. Robot-wide interfaces go on or beneath the RosContextAPI prim; sensor interfaces go on a child Xform of the physical link, one interface per prim. Interface prims must reside outside payloads and do not generate TF frames. @@ -134,7 +134,7 @@ class "Ros2TopicAPI" ( # Core Attributes (Required) # ------------------------------------------------------------------ - uniform token ros2:topic:role ( + uniform token ros:topic:role ( customData = { string apiName = "role" } @@ -143,17 +143,17 @@ class "Ros2TopicAPI" ( subscription.""" ) - uniform string ros2:topic:name ( + uniform string ros:topic:name ( customData = { string apiName = "name" } doc = """The topic name, relative to the active ROS 2 namespace - inherited from the nearest ancestor Ros2ContextAPI. Must adhere + inherited from the nearest ancestor RosContextAPI. Must adhere to ROS 2 topic naming rules (alphanumeric, underscores, and forward slashes only; cannot start with a number).""" ) - uniform string ros2:topic:type ( + uniform string ros:topic:type ( customData = { string apiName = "type" } @@ -163,7 +163,7 @@ class "Ros2TopicAPI" ( must safely disable this interface and emit a warning.""" ) - uniform double ros2:topic:publish_rate ( + uniform double ros:topic:publish_rate ( customData = { string apiName = "publishRate" } @@ -175,7 +175,7 @@ class "Ros2TopicAPI" ( # Quality of Service (QoS) Attributes # ------------------------------------------------------------------ - uniform bool ros2:topic:qos:match_publisher = false ( + uniform bool ros:topic:qos:match_publisher = false ( customData = { string apiName = "qosMatchPublisher" } @@ -184,7 +184,7 @@ class "Ros2TopicAPI" ( publisher, ignoring explicit reliability and durability settings.""" ) - uniform token ros2:topic:qos:reliability = "system_default" ( + uniform token ros:topic:qos:reliability = "system_default" ( customData = { string apiName = "qosReliability" } @@ -194,7 +194,7 @@ class "Ros2TopicAPI" ( which maps to best-effort.""" ) - uniform token ros2:topic:qos:durability = "system_default" ( + uniform token ros:topic:qos:durability = "system_default" ( customData = { string apiName = "qosDurability" } @@ -203,7 +203,7 @@ class "Ros2TopicAPI" ( publishers should use 'transient_local'.""" ) - uniform token ros2:topic:qos:history = "system_default" ( + uniform token ros:topic:qos:history = "system_default" ( customData = { string apiName = "qosHistory" } @@ -211,7 +211,7 @@ class "Ros2TopicAPI" ( doc = """Maps to rmw_qos_profile_t history policy.""" ) - uniform int ros2:topic:qos:depth = 10 ( + uniform int ros:topic:qos:depth = 10 ( customData = { string apiName = "qosDepth" } @@ -220,10 +220,10 @@ class "Ros2TopicAPI" ( } # ====================================================================== -# Section 2.5 - Ros2ServiceAPI +# Section 2.5 - RosServiceAPI # ====================================================================== -class "Ros2ServiceAPI" ( +class "RosServiceAPI" ( inherits = customData = { token apiSchemaType = "singleApply" @@ -232,11 +232,11 @@ class "Ros2ServiceAPI" ( doc = """Applied to prims handling synchronous ROS 2 requests. Simulators spawn the corresponding server or client at runtime. - Same placement, resolution, and TF exclusion rules as Ros2TopicAPI. + Same placement, resolution, and TF exclusion rules as RosTopicAPI. """ ) { - uniform token ros2:service:role ( + uniform token ros:service:role ( customData = { string apiName = "role" } @@ -245,7 +245,7 @@ class "Ros2ServiceAPI" ( client. Simulation assets are typically servers.""" ) - uniform string ros2:service:name ( + uniform string ros:service:name ( customData = { string apiName = "name" } @@ -253,7 +253,7 @@ class "Ros2ServiceAPI" ( Must adhere to ROS 2 naming rules.""" ) - uniform string ros2:service:type ( + uniform string ros:service:type ( customData = { string apiName = "type" } @@ -263,10 +263,10 @@ class "Ros2ServiceAPI" ( } # ====================================================================== -# Section 2.6 - Ros2ActionAPI +# Section 2.6 - RosActionAPI # ====================================================================== -class "Ros2ActionAPI" ( +class "RosActionAPI" ( inherits = customData = { token apiSchemaType = "singleApply" @@ -275,11 +275,11 @@ class "Ros2ActionAPI" ( doc = """Applied to prims handling asynchronous, long-running ROS 2 behaviors. Simulators spawn the corresponding server or client at runtime. - Same placement, resolution, and TF exclusion rules as Ros2TopicAPI. + Same placement, resolution, and TF exclusion rules as RosTopicAPI. """ ) { - uniform token ros2:action:role ( + uniform token ros:action:role ( customData = { string apiName = "role" } @@ -288,7 +288,7 @@ class "Ros2ActionAPI" ( client. Simulation assets are typically servers.""" ) - uniform string ros2:action:name ( + uniform string ros:action:name ( customData = { string apiName = "name" } @@ -296,7 +296,7 @@ class "Ros2ActionAPI" ( Must adhere to ROS 2 naming rules.""" ) - uniform string ros2:action:type ( + uniform string ros:action:type ( customData = { string apiName = "type" } @@ -307,10 +307,10 @@ class "Ros2ActionAPI" ( } # ====================================================================== -# Section 2.7 - Ros2FrameAPI +# Section 2.7 - RosFrameAPI # ====================================================================== -class "Ros2FrameAPI" ( +class "RosFrameAPI" ( inherits = customData = { token apiSchemaType = "singleApply" @@ -325,7 +325,7 @@ class "Ros2FrameAPI" ( """ ) { - uniform string ros2:frame:id ( + uniform string ros:frame:id ( customData = { string apiName = "id" } @@ -333,7 +333,7 @@ class "Ros2FrameAPI" ( Prim name is used as the frame_id.""" ) - uniform bool ros2:frame:static = true ( + uniform bool ros:frame:static = true ( customData = { string apiName = "static" } @@ -352,20 +352,20 @@ class "Ros2FrameAPI" ( # The simulator exposes joint state and command interfaces to an # external control algorithm. The interface shape is simulator- # specific (e.g. ros2_control hardware_interface, IPC, HIL). -# Prims are marked with Ros2ExternalControlAPI as a built-in. +# Prims are marked with RosExternalControlAPI as a built-in. # # Application-level (integrated) simulation (Section 4.2): # The controller runs inside the simulator and is configured via # prim parameters and ROS communication. Prims are marked with -# Ros2IntegratedControlAPI as a built-in and reference topic, +# RosIntegratedControlAPI as a built-in and reference topic, # service, or action interface prims. # ====================================================================== # ====================================================================== -# Section 4.1 - Ros2ExternalControlAPI +# Section 4.1 - RosExternalControlAPI # ====================================================================== -class "Ros2ExternalControlAPI" ( +class "RosExternalControlAPI" ( inherits = customData = { token apiSchemaType = "singleApply" @@ -384,10 +384,10 @@ class "Ros2ExternalControlAPI" ( } # ====================================================================== -# Section 4.2 - Ros2IntegratedControlAPI +# Section 4.2 - RosIntegratedControlAPI # ====================================================================== -class "Ros2IntegratedControlAPI" ( +class "RosIntegratedControlAPI" ( inherits = customData = { token apiSchemaType = "singleApply" @@ -398,8 +398,8 @@ class "Ros2IntegratedControlAPI" ( Included as a built-in via 'prepend apiSchemas' by simulator-specific or standardized controller schemas that run the controller logic inside the simulator. All prims referenced by a controller that - inherits this schema must have at least one of Ros2TopicAPI, - Ros2ServiceAPI, or Ros2ActionAPI applied. USD does not enforce this + inherits this schema must have at least one of RosTopicAPI, + RosServiceAPI, or RosActionAPI applied. USD does not enforce this constraint at the schema level; simulators are responsible for runtime validation. """ @@ -408,12 +408,12 @@ class "Ros2IntegratedControlAPI" ( } # ====================================================================== -# Section 4.2.1.1 - Ros2RigidBodyTwistControllerAPI +# Section 4.2.1.1 - RosRigidBodyTwistControllerAPI # ====================================================================== -class "Ros2RigidBodyTwistControllerAPI" ( +class "RosRigidBodyTwistControllerAPI" ( inherits = - prepend apiSchemas = ["Ros2IntegratedControlAPI"] + prepend apiSchemas = ["RosIntegratedControlAPI"] customData = { token apiSchemaType = "singleApply" string className = "RigidBodyTwistControllerAPI" @@ -427,15 +427,15 @@ class "Ros2RigidBodyTwistControllerAPI" ( """ ) { - rel ros2:rigid_body_twist:subscriber ( + rel ros:rigid_body_twist:subscriber ( customData = { string apiName = "subscriber" } - doc = """Reference to a prim with Ros2TopicAPI configured as a + doc = """Reference to a prim with RosTopicAPI configured as a subscription for geometry_msgs/Twist control messages.""" ) - rel ros2:rigid_body_twist:body ( + rel ros:rigid_body_twist:body ( customData = { string apiName = "body" } @@ -443,7 +443,7 @@ class "Ros2RigidBodyTwistControllerAPI" ( the commanded velocities are applied.""" ) - uniform double ros2:rigid_body_twist:cmd_vel_timeout = 0.5 ( + uniform double ros:rigid_body_twist:cmd_vel_timeout = 0.5 ( customData = { string apiName = "cmdVelTimeout" } @@ -451,28 +451,28 @@ class "Ros2RigidBodyTwistControllerAPI" ( considered stale and the body velocity is zeroed.""" ) - uniform double ros2:rigid_body_twist:linear:x:max_velocity ( + uniform double ros:rigid_body_twist:linear:x:max_velocity ( customData = { string apiName = "linearXMaxVelocity" } doc = """Maximum linear velocity along the X axis in m/s.""" ) - uniform double ros2:rigid_body_twist:linear:x:max_acceleration ( + uniform double ros:rigid_body_twist:linear:x:max_acceleration ( customData = { string apiName = "linearXMaxAcceleration" } doc = """Maximum linear acceleration along the X axis in m/s².""" ) - uniform double ros2:rigid_body_twist:angular:z:max_velocity ( + uniform double ros:rigid_body_twist:angular:z:max_velocity ( customData = { string apiName = "angularZMaxVelocity" } doc = """Maximum angular velocity around the Z axis in rad/s.""" ) - uniform double ros2:rigid_body_twist:angular:z:max_acceleration ( + uniform double ros:rigid_body_twist:angular:z:max_acceleration ( customData = { string apiName = "angularZMaxAcceleration" } @@ -481,12 +481,12 @@ class "Ros2RigidBodyTwistControllerAPI" ( } # ====================================================================== -# Section 4.2.1.2 - Ros2DiffDriveControllerAPI +# Section 4.2.1.2 - RosDiffDriveControllerAPI # ====================================================================== -class "Ros2DiffDriveControllerAPI" ( +class "RosDiffDriveControllerAPI" ( inherits = - prepend apiSchemas = ["Ros2IntegratedControlAPI"] + prepend apiSchemas = ["RosIntegratedControlAPI"] customData = { token apiSchemaType = "singleApply" string className = "DiffDriveControllerAPI" @@ -501,23 +501,23 @@ class "Ros2DiffDriveControllerAPI" ( """ ) { - rel ros2:diff_drive:subscriber ( + rel ros:diff_drive:subscriber ( customData = { string apiName = "subscriber" } - doc = """Reference to a prim with Ros2TopicAPI configured as a + doc = """Reference to a prim with RosTopicAPI configured as a subscription for geometry_msgs/Twist velocity commands.""" ) - rel ros2:diff_drive:odom ( + rel ros:diff_drive:odom ( customData = { string apiName = "odom" } - doc = """Reference to a prim with Ros2TopicAPI configured as a + doc = """Reference to a prim with RosTopicAPI configured as a publisher for nav_msgs/Odometry data.""" ) - rel ros2:diff_drive:left_wheels ( + rel ros:diff_drive:left_wheels ( customData = { string apiName = "leftWheels" } @@ -525,7 +525,7 @@ class "Ros2DiffDriveControllerAPI" ( the left wheel joints.""" ) - rel ros2:diff_drive:right_wheels ( + rel ros:diff_drive:right_wheels ( customData = { string apiName = "rightWheels" } @@ -533,7 +533,7 @@ class "Ros2DiffDriveControllerAPI" ( the right wheel joints.""" ) - uniform double ros2:diff_drive:wheel_separation ( + uniform double ros:diff_drive:wheel_separation ( customData = { string apiName = "wheelSeparation" } @@ -541,14 +541,14 @@ class "Ros2DiffDriveControllerAPI" ( in meters.""" ) - uniform double ros2:diff_drive:wheel_radius ( + uniform double ros:diff_drive:wheel_radius ( customData = { string apiName = "wheelRadius" } doc = """Radius of the wheels in meters.""" ) - uniform double ros2:diff_drive:cmd_vel_timeout = 0.5 ( + uniform double ros:diff_drive:cmd_vel_timeout = 0.5 ( customData = { string apiName = "cmdVelTimeout" } @@ -556,28 +556,28 @@ class "Ros2DiffDriveControllerAPI" ( considered stale and wheel velocities are zeroed.""" ) - uniform double ros2:diff_drive:linear:x:max_velocity ( + uniform double ros:diff_drive:linear:x:max_velocity ( customData = { string apiName = "linearXMaxVelocity" } doc = """Maximum linear velocity along the X axis in m/s.""" ) - uniform double ros2:diff_drive:linear:x:max_acceleration ( + uniform double ros:diff_drive:linear:x:max_acceleration ( customData = { string apiName = "linearXMaxAcceleration" } doc = """Maximum linear acceleration along the X axis in m/s².""" ) - uniform double ros2:diff_drive:angular:z:max_velocity ( + uniform double ros:diff_drive:angular:z:max_velocity ( customData = { string apiName = "angularZMaxVelocity" } doc = """Maximum angular velocity around the Z axis in rad/s.""" ) - uniform double ros2:diff_drive:angular:z:max_acceleration ( + uniform double ros:diff_drive:angular:z:max_acceleration ( customData = { string apiName = "angularZMaxAcceleration" } @@ -586,12 +586,12 @@ class "Ros2DiffDriveControllerAPI" ( } # ====================================================================== -# Section 4.2.1.3 - Ros2JointTrajectoryControllerAPI +# Section 4.2.1.3 - RosJointTrajectoryControllerAPI # ====================================================================== -class "Ros2JointTrajectoryControllerAPI" ( +class "RosJointTrajectoryControllerAPI" ( inherits = - prepend apiSchemas = ["Ros2IntegratedControlAPI"] + prepend apiSchemas = ["RosIntegratedControlAPI"] customData = { token apiSchemaType = "singleApply" string className = "JointTrajectoryControllerAPI" @@ -604,25 +604,25 @@ class "Ros2JointTrajectoryControllerAPI" ( """ ) { - rel ros2:joint_trajectory:server ( + rel ros:joint_trajectory:server ( customData = { string apiName = "server" } - doc = """Reference to a prim with Ros2ActionAPI configured as a + doc = """Reference to a prim with RosActionAPI configured as a server for control_msgs/FollowJointTrajectory action goals.""" ) - rel ros2:joint_trajectory:command_joints ( + rel ros:joint_trajectory:command_joints ( customData = { string apiName = "commandJoints" } doc = """References to prims with UsdPhysicsJointAPI representing the joints to be commanded along the trajectory. Simulators must - use the ros2:joint:name custom property for joint name mapping, + use the ros:joint:name custom property for joint name mapping, falling back to the prim name if absent.""" ) - uniform double ros2:joint_trajectory:action_monitor_rate ( + uniform double ros:joint_trajectory:action_monitor_rate ( customData = { string apiName = "actionMonitorRate" } @@ -630,7 +630,7 @@ class "Ros2JointTrajectoryControllerAPI" ( is monitored.""" ) - uniform double ros2:joint_trajectory:stopped_velocity_tolerance ( + uniform double ros:joint_trajectory:stopped_velocity_tolerance ( customData = { string apiName = "stoppedVelocityTolerance" } @@ -638,7 +638,7 @@ class "Ros2JointTrajectoryControllerAPI" ( which the controlled system is considered stopped.""" ) - uniform double ros2:joint_trajectory:timeout ( + uniform double ros:joint_trajectory:timeout ( customData = { string apiName = "timeout" } @@ -648,12 +648,12 @@ class "Ros2JointTrajectoryControllerAPI" ( } # ====================================================================== -# Section 4.2.1.4 - Ros2JointStateBroadcasterAPI +# Section 4.2.1.4 - RosJointStateBroadcasterAPI # ====================================================================== -class "Ros2JointStateBroadcasterAPI" ( +class "RosJointStateBroadcasterAPI" ( inherits = - prepend apiSchemas = ["Ros2IntegratedControlAPI"] + prepend apiSchemas = ["RosIntegratedControlAPI"] customData = { token apiSchemaType = "singleApply" string className = "JointStateBroadcasterAPI" @@ -665,32 +665,32 @@ class "Ros2JointStateBroadcasterAPI" ( """ ) { - rel ros2:joint_state_broadcaster:publisher ( + rel ros:joint_state_broadcaster:publisher ( customData = { string apiName = "publisher" } - doc = """Reference to a prim with Ros2TopicAPI configured as a + doc = """Reference to a prim with RosTopicAPI configured as a publisher for sensor_msgs/JointState messages.""" ) - rel ros2:joint_state_broadcaster:joints ( + rel ros:joint_state_broadcaster:joints ( customData = { string apiName = "joints" } doc = """References to prims with UsdPhysicsJointAPI representing the joints whose states are to be broadcast. Simulators must use - the ros2:joint:name custom property for joint name mapping, + the ros:joint:name custom property for joint name mapping, falling back to the prim name if absent.""" ) - uniform double ros2:joint_state_broadcaster:publish_rate ( + uniform double ros:joint_state_broadcaster:publish_rate ( customData = { string apiName = "publishRate" } doc = """Frequency in Hz at which joint states are published.""" ) - uniform string ros2:joint_state_broadcaster:frame_id ( + uniform string ros:joint_state_broadcaster:frame_id ( customData = { string apiName = "frameId" } From 069c363b3e0becd3d4e6cb7c43eecb07a9f6263d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Tue, 7 Apr 2026 11:12:01 +0200 Subject: [PATCH 067/111] Update rep.md MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Michał Pełka Signed-off-by: Adam Dabrowski --- rep.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rep.md b/rep.md index 98ea582..d401d0f 100644 --- a/rep.md +++ b/rep.md @@ -351,7 +351,7 @@ 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 +Simulators may choose to implement additional controllers as needed for their specific use cases and robot types, but these four 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. From 463d02a0e540f52f42eaa42c7505ffedb714f53a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Micha=C5=82=20Pe=C5=82ka?= Date: Wed, 8 Apr 2026 13:17:18 +0200 Subject: [PATCH 068/111] Apply suggestions from code review MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Adam Dąbrowski Co-authored-by: Mateusz Żak Co-authored-by: Michał Pełka Signed-off-by: Adam Dabrowski --- rep.md | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/rep.md b/rep.md index d401d0f..ea3b63f 100644 --- a/rep.md +++ b/rep.md @@ -251,8 +251,8 @@ Simulator-level interfaces are prohibited in assets to avoid clashes, including: ======= ### 2.10 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. +Number of concepts in ROS (e.g. robot descriptions, controllers) rely 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 ``). If this property is missing, simulators must fall back to using the prim name. >>>>>>> 84b460b (Added `ros2:joint:name` custom attribute instead of ROS2JointAPI schema.) @@ -384,10 +384,11 @@ The computed velocities should be applied to prims with `UsdPhysicsDriveAPI` (pa 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:subscriber`: relationship targeting a prim with the RosTopicAPI with `role="subscription"` that provides the velocity commands for this controller. + - `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. +- `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`. @@ -406,7 +407,7 @@ 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`. +- `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 @@ -420,8 +421,8 @@ Implementation should follow logic similar to the `joint_state_broadcaster` in ` 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. +- `rel ros:joint_state_broadcaster:publisher`: relationship targeting a prim with the RosTopicAPI with `role="publisher"` for 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. From 0a3991186438f21b67a5adf466fa5eb0771c0ae6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Micha=C5=82=20Pe=C5=82ka?= Date: Wed, 8 Apr 2026 15:15:18 +0200 Subject: [PATCH 069/111] applied review comments MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Michał Pełka Signed-off-by: Adam Dabrowski --- rep.md | 28 +++++++++------------------- schema/schema.usda | 4 ++-- 2 files changed, 11 insertions(+), 21 deletions(-) diff --git a/rep.md b/rep.md index ea3b63f..77a2b80 100644 --- a/rep.md +++ b/rep.md @@ -336,7 +336,7 @@ and expose the control and state interfaces to control entity. `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: +Example can be `simulatorXYZ::ROSCustomTwistControllerAPI` which will include as built-in `RosIntegratedControlAPI` and reference prims: - `ROSTopicAPI` for subscription of control message. - `PhysicsRigidBodyAPI` for interaction with the physics engine. @@ -346,8 +346,8 @@ USD does not enforce API schema constraints on referenced prims at the schema d 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. +Simulators may implement these schemas to provide a standardized control interface for common use cases. +Such usecase can be different robot locomotion (e.g. Ackermann car-like robot) or application specific itnrfaces (e.g., joint control interface for robot policy). 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. @@ -360,20 +360,12 @@ The implementation should allow performing multi-robot simulation and control by 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. - +This implementation provides a general-purpose controller for applying velocity to a rigid body in a generalized manner. - `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 @@ -391,7 +383,7 @@ Implementation should follow logic similar to the `diff_drive_controller` in `ro - `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:cmd_vel_timeout`: Timeout in seconds after which the command is considered stale. Exposed as dynamic paramter. - `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. @@ -407,11 +399,10 @@ 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`. +- `rel ros:joint_trajectory:command_joints`: References to prims with `UsdPhysicsJoint`. - `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:stopped_velocity_tolerance`: Velocity tolerance at the end of the trajectory that indicates the controlled system has stopped. Exposed as dynamic paramter. - `double ros:joint_trajectory:timeout`: Maximum time allowed to reach the trajectory goal. #### 4.2.1.4 ROSJointStateBroadcasterAPI @@ -419,11 +410,10 @@ use it for mapping trajectory points to joints in the simulator. 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. +property of the joint prims and use it for mapping joints in the simulator to those in robot description or application. - `rel ros:joint_state_broadcaster:publisher`: relationship targeting a prim with the RosTopicAPI with `role="publisher"` for 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. +- `rel ros:joint_state_broadcaster:joints`: References to prims with `UsdPhysicsJoint` representing the joints whose states are to be broadcast. - `string ros:joint_state_broadcaster:frame_id`: The TF frame ID to be used in the published JointState messages. ## Tools diff --git a/schema/schema.usda b/schema/schema.usda index 5978ace..75e488c 100644 --- a/schema/schema.usda +++ b/schema/schema.usda @@ -616,7 +616,7 @@ class "RosJointTrajectoryControllerAPI" ( customData = { string apiName = "commandJoints" } - doc = """References to prims with UsdPhysicsJointAPI representing + doc = """References to prims with UsdPhysicsJoint representing the joints to be commanded along the trajectory. Simulators must use the ros:joint:name custom property for joint name mapping, falling back to the prim name if absent.""" @@ -677,7 +677,7 @@ class "RosJointStateBroadcasterAPI" ( customData = { string apiName = "joints" } - doc = """References to prims with UsdPhysicsJointAPI representing + doc = """References to prims with UsdPhysicsJoint representing the joints whose states are to be broadcast. Simulators must use the ros:joint:name custom property for joint name mapping, falling back to the prim name if absent.""" From 5d761493bd7bb314bf96d28519322acd42097f0a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Micha=C5=82=20Pe=C5=82ka?= Date: Fri, 10 Apr 2026 15:51:58 +0200 Subject: [PATCH 070/111] Move control to extension MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Michał Pełka Signed-off-by: Adam Dabrowski --- control/control_extension.md | 119 ++++++++++++ control/schema/schema.usda | 339 +++++++++++++++++++++++++++++++++++ rep.md | 111 +----------- 3 files changed, 463 insertions(+), 106 deletions(-) create mode 100644 control/control_extension.md create mode 100644 control/schema/schema.usda diff --git a/control/control_extension.md b/control/control_extension.md new file mode 100644 index 0000000..cce530f --- /dev/null +++ b/control/control_extension.md @@ -0,0 +1,119 @@ +# REP XXXX -- OpenUSD Conventions for Simulation Asset Interoperability - Control Extension + +## Abstract + +This document defines conventions for simulating robotic systems in OpenUSD, with a focus on control interfaces and integration with ROS 2. +It proposes standardized API schemas for exposing robot control interfaces to external control algorithms and for instantiating robot controllers directly within the simulated scene. +The goal is to enable modular and scalable robotic simulation that can be easily integrated with ROS 2-based control frameworks. + +## 1. Controllers + +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. + + +### 1.1 External Control Interfaces + +The ROS 2 external control `RosControlExternalAPI` 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. + +### 1.2 Integrated Controller Simulation + +`RosControlIntegratedAPI` 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::RosCustomTwistControllerAPI` which will include as built-in `RosControlIntegratedAPI` 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`. + +### 1.2.1 Built-in Controllers + +The following schemas are built-in controller schemas that include `RosControlIntegratedAPI` as a built-in via `prepend apiSchemas`. +Simulators may implement these schemas to provide a standardized control interface for common use cases. +Such usecase can be different robot locomotion (e.g. Ackermann car-like robot) or application specific interfaces (e.g., joint control interface for robot policy). +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 four 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. + +#### 1.2.1.1 RosControlRigidBodyTwistAPI + +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. +This implementation provides a general-purpose controller for applying velocity to a rigid body in a generalized manner. +- `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. + +#### 1.2.1.2 RosControlDiffDriveAPI + +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`: relationship targeting a prim with the RosTopicAPI with `role="subscription"` that provides the velocity commands for this controller. + +- `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. Exposed as dynamic parameter. +- `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². + +#### 1.2.1.3 RosControlJointTrajectoryAPI + +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 `UsdPhysicsJoint`. +- `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. Exposed as dynamic parameter. +- `double ros:joint_trajectory:timeout`: Maximum time allowed to reach the trajectory goal. + +#### 1.2.1.4 RosControlJointStateBroadcasterAPI + +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 joints in the simulator to those in robot description or application. + +- `rel ros:joint_state_broadcaster:publisher`: relationship targeting a prim with the RosTopicAPI with `role="publisher"` for joint state data. +- `rel ros:joint_state_broadcaster:joints`: References to prims with `UsdPhysicsJoint` representing the joints whose states are to be broadcast. +- `string ros:joint_state_broadcaster:frame_id`: The TF frame ID to be used in the published JointState messages. + +## Tools + +### Schema Definition +The normative OpenUSD schema definition for all `RosControl*API` schemas is provided in `schema/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. + diff --git a/control/schema/schema.usda b/control/schema/schema.usda new file mode 100644 index 0000000..41b1530 --- /dev/null +++ b/control/schema/schema.usda @@ -0,0 +1,339 @@ +#usda 1.0 +( + "ROS Integration Schemas for OpenUSD Simulation Asset Interoperability." + " Defines declarative, engine-agnostic API schemas for ROS interfaces" + " as specified in REP-XXXX, Section 2." + subLayers = [ + @usd/schema.usda@ + ] +) + +over "GLOBAL" ( + customData = { + string libraryName = "usdRosControl" + string libraryPath = "usdRosControl" + string libraryPrefix = "usdRosControl" + dictionary libraryTokens = { + } + } +) +{ +} + +# ====================================================================== +# Robot Control Schemas +# Two approaches to simulating a robotic system are defined: +# +# Control-level simulation (Section 1.1): +# The simulator exposes joint state and command interfaces to an +# external control algorithm. The interface shape is simulator- +# specific (e.g. ros2_control hardware_interface, IPC, HIL). +# Prims are marked with RosControlExternalAPI as a built-in. +# +# Application-level (integrated) simulation (Section 1.2): +# The controller runs inside the simulator and is configured via +# prim parameters and ROS communication. Prims are marked with +# RosControlIntegratedAPI as a built-in and reference topic, +# service, or action interface prims. +# ====================================================================== + +# ====================================================================== +# Section 1.1 - RosControlExternalAPI +# ====================================================================== + +class "RosControlExternalAPI" ( + inherits = + customData = { + token apiSchemaType = "singleApply" + string className = "RosControlExternalAPI" + } + doc = """Base schema for exposing robot control interfaces to external control algorithms. + + Applied (via 'prepend apiSchemas') by simulator-specific schemas to + identify prims whose joint state and command interfaces should be + exposed to an external control entity (e.g. a ros2_control + hardware_interface plugin, an inter-process controller, or a + hardware-in-the-loop connection). + """ +) +{ +} + +# ====================================================================== +# Section 1.2 - RosControlIntegratedAPI +# ====================================================================== + +class "RosControlIntegratedAPI" ( + inherits = + customData = { + token apiSchemaType = "singleApply" + string className = "RosControlIntegratedAPI" + } + doc = """Base schema for integrated (application-level) robot controllers. + + Included as a built-in via 'prepend apiSchemas' by simulator-specific + or standardized controller schemas that run the controller logic + inside the simulator. All prims referenced by a controller that + inherits this schema must have at least one of RosTopicAPI, + RosServiceAPI, or RosActionAPI applied. USD does not enforce this + constraint at the schema level; simulators are responsible for + runtime validation. + """ +) +{ +} + +# ====================================================================== +# Section 1.2.1.1 - RosControlRigidBodyTwistAPI +# ====================================================================== + +class "RosControlRigidBodyTwistAPI" ( + inherits = + prepend apiSchemas = ["RosControlIntegratedAPI"] + customData = { + token apiSchemaType = "singleApply" + string className = "RosControlRigidBodyTwistAPI" + } + doc = """Controls a rigid body via geometry_msgs/Twist messages. + + Subscribes to a Twist topic and applies the commanded linear and + angular velocities directly to a rigid body in the physics engine, + with optional velocity and acceleration limits. + """ +) +{ + rel ros:rigid_body_twist:subscriber ( + customData = { + string apiName = "subscriber" + } + doc = """Reference to a prim with RosTopicAPI configured as a + subscription for geometry_msgs/Twist control messages.""" + ) + + rel ros:rigid_body_twist:body ( + customData = { + string apiName = "body" + } + doc = """Reference to a prim with UsdPhysicsRigidBodyAPI to which + the commanded velocities are applied.""" + ) +} + +# ====================================================================== +# Section 1.2.1.2 - RosControlDiffDriveAPI +# ====================================================================== + +class "RosControlDiffDriveAPI" ( + inherits = + prepend apiSchemas = ["RosControlIntegratedAPI"] + customData = { + token apiSchemaType = "singleApply" + string className = "RosControlDiffDriveAPI" + } + doc = """Controls a differential drive robot via geometry_msgs/Twist messages. + + Subscribes to a Twist topic, converts commanded linear and angular + velocities into individual wheel velocities, and applies them to + wheel joint prims with UsdPhysicsDriveAPI. Publishes odometry data + as nav_msgs/Odometry. Implementation should follow logic similar to + the diff_drive_controller in ros2_controllers. + """ +) +{ + rel ros:diff_drive:subscriber ( + customData = { + string apiName = "subscriber" + } + doc = """Reference to a prim with RosTopicAPI configured as a + subscription for geometry_msgs/Twist velocity commands.""" + ) + + rel ros:diff_drive:odom ( + customData = { + string apiName = "odom" + } + doc = """Reference to a prim with RosTopicAPI configured as a + publisher for nav_msgs/Odometry data.""" + ) + + rel ros:diff_drive:left_wheels ( + customData = { + string apiName = "leftWheels" + } + doc = """References to prims with UsdPhysicsDriveAPI representing + the left wheel joints.""" + ) + + rel ros:diff_drive:right_wheels ( + customData = { + string apiName = "rightWheels" + } + doc = """References to prims with UsdPhysicsDriveAPI representing + the right wheel joints.""" + ) + + uniform double ros:diff_drive:wheel_separation ( + customData = { + string apiName = "wheelSeparation" + } + doc = """Distance between the left and right wheel contact points + in meters.""" + ) + + uniform double ros:diff_drive:wheel_radius ( + customData = { + string apiName = "wheelRadius" + } + doc = """Radius of the wheels in meters.""" + ) + + uniform double ros:diff_drive:cmd_vel_timeout = 0.5 ( + customData = { + string apiName = "cmdVelTimeout" + } + doc = """Timeout in seconds after which a velocity command is + considered stale and wheel velocities are zeroed.""" + ) + + uniform double ros:diff_drive:linear:x:max_velocity ( + customData = { + string apiName = "linearXMaxVelocity" + } + doc = """Maximum linear velocity along the X axis in m/s.""" + ) + + uniform double ros:diff_drive:linear:x:max_acceleration ( + customData = { + string apiName = "linearXMaxAcceleration" + } + doc = """Maximum linear acceleration along the X axis in m/s².""" + ) + + uniform double ros:diff_drive:angular:z:max_velocity ( + customData = { + string apiName = "angularZMaxVelocity" + } + doc = """Maximum angular velocity around the Z axis in rad/s.""" + ) + + uniform double ros:diff_drive:angular:z:max_acceleration ( + customData = { + string apiName = "angularZMaxAcceleration" + } + doc = """Maximum angular acceleration around the Z axis in rad/s².""" + ) +} + +# ====================================================================== +# Section 1.2.1.3 - RosControlJointTrajectoryAPI +# ====================================================================== + +class "RosControlJointTrajectoryAPI" ( + inherits = + prepend apiSchemas = ["RosControlIntegratedAPI"] + customData = { + token apiSchemaType = "singleApply" + string className = "RosControlJointTrajectoryAPI" + } + doc = """Executes joint trajectories via control_msgs/FollowJointTrajectory actions. + + Accepts action goals and commands the simulator to follow the + specified joint trajectory. Implementation should follow logic + similar to the joint_trajectory_controller in ros2_controllers. + """ +) +{ + rel ros:joint_trajectory:server ( + customData = { + string apiName = "server" + } + doc = """Reference to a prim with RosActionAPI configured as a + server for control_msgs/FollowJointTrajectory action goals.""" + ) + + rel ros:joint_trajectory:command_joints ( + customData = { + string apiName = "commandJoints" + } + doc = """References to prims with UsdPhysicsJoint representing + the joints to be commanded along the trajectory. Simulators must + use the ros:joint:name custom property for joint name mapping, + falling back to the prim name if absent.""" + ) + + uniform double ros:joint_trajectory:action_monitor_rate ( + customData = { + string apiName = "actionMonitorRate" + } + doc = """Frequency in Hz at which trajectory execution progress + is monitored.""" + ) + + uniform double ros:joint_trajectory:stopped_velocity_tolerance ( + customData = { + string apiName = "stoppedVelocityTolerance" + } + doc = """Velocity tolerance at the end of the trajectory below + which the controlled system is considered stopped.""" + ) + + uniform double ros:joint_trajectory:timeout ( + customData = { + string apiName = "timeout" + } + doc = """Maximum time in seconds allowed to reach the trajectory + goal before the action is aborted.""" + ) +} + +# ====================================================================== +# Section 1.2.1.4 - RosControlJointStateBroadcasterAPI +# ====================================================================== + +class "RosControlJointStateBroadcasterAPI" ( + inherits = + prepend apiSchemas = ["RosControlIntegratedAPI"] + customData = { + token apiSchemaType = "singleApply" + string className = "RosControlJointStateBroadcasterAPI" + } + doc = """Reads joint states and publishes them as sensor_msgs/JointState messages. + + Implementation should follow logic similar to the + joint_state_broadcaster in ros2_controllers. + """ +) +{ + rel ros:joint_state_broadcaster:publisher ( + customData = { + string apiName = "publisher" + } + doc = """Reference to a prim with RosTopicAPI configured as a + publisher for sensor_msgs/JointState messages.""" + ) + + rel ros:joint_state_broadcaster:joints ( + customData = { + string apiName = "joints" + } + doc = """References to prims with UsdPhysicsJoint representing + the joints whose states are to be broadcast. Simulators must use + the ros:joint:name custom property for joint name mapping, + falling back to the prim name if absent.""" + ) + + uniform double ros:joint_state_broadcaster:publish_rate ( + customData = { + string apiName = "publishRate" + } + doc = """Frequency in Hz at which joint states are published.""" + ) + + uniform string ros:joint_state_broadcaster:frame_id ( + customData = { + string apiName = "frameId" + } + doc = """The TF frame_id to be used in the published JointState + messages.""" + ) +} diff --git a/rep.md b/rep.md index 77a2b80..5176ed0 100644 --- a/rep.md +++ b/rep.md @@ -309,112 +309,11 @@ 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 ``, MJCF ``). Obsolete approaches such as injecting legacy `` 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::ROSCustomTwistControllerAPI` which will include as built-in `RosIntegratedControlAPI` 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. -Such usecase can be different robot locomotion (e.g. Ackermann car-like robot) or application specific itnrfaces (e.g., joint control interface for robot policy). -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 four 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. -This implementation provides a general-purpose controller for applying velocity to a rigid body in a generalized manner. -- `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. - -#### 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`: relationship targeting a prim with the RosTopicAPI with `role="subscription"` that provides the velocity commands for this controller. - -- `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. Exposed as dynamic paramter. -- `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 `UsdPhysicsJoint`. -- `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. Exposed as dynamic paramter. -- `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 joints in the simulator to those in robot description or application. - -- `rel ros:joint_state_broadcaster:publisher`: relationship targeting a prim with the RosTopicAPI with `role="publisher"` for joint state data. -- `rel ros:joint_state_broadcaster:joints`: References to prims with `UsdPhysicsJoint` representing the joints whose states are to be broadcast. -- `string ros:joint_state_broadcaster:frame_id`: The TF frame ID to be used in the published JointState messages. +## Extensions + +A number of features (e.g., control interfaces, sensors specification) are proposed to extend this schema. +These extensions are not required for compliance with the core REP, but are recommended for simulators targeting interoperability with ROS. +They will be defined in future iterations of this document and shared with the community for feedback. ## Tools From 034f00f3f1ba58e93a4f8277570dd66c1cdec76e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Micha=C5=82=20Pe=C5=82ka?= Date: Mon, 13 Apr 2026 13:17:20 +0200 Subject: [PATCH 071/111] Fixed error in merge, fixed links MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Michał Pełka Signed-off-by: Adam Dabrowski --- control/control_extension.md | 4 +- control/schema/schema.usda | 14 -- rep.md | 4 - schema/schema.usda | 356 ----------------------------------- 4 files changed, 2 insertions(+), 376 deletions(-) diff --git a/control/control_extension.md b/control/control_extension.md index cce530f..80c4463 100644 --- a/control/control_extension.md +++ b/control/control_extension.md @@ -31,7 +31,7 @@ and expose the control and state interfaces to control entity. ### 1.2 Integrated Controller Simulation `RosControlIntegratedAPI` 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). +It must reference one or more prims that have [RosTopicAPI](../rep.md#24-topic-interface-rostopicapi), [RosServiceAPI](../rep.md#25-service-interface-rosserviceapi) or [RosActionAPI](../rep.md#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::RosCustomTwistControllerAPI` which will include as built-in `RosControlIntegratedAPI` and reference prims: - `RosTopicAPI` for subscription of control message. @@ -90,7 +90,7 @@ Implementation should follow logic similar to the `diff_drive_controller` in `ro 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 +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` diff --git a/control/schema/schema.usda b/control/schema/schema.usda index 41b1530..cbca7ec 100644 --- a/control/schema/schema.usda +++ b/control/schema/schema.usda @@ -322,18 +322,4 @@ class "RosControlJointStateBroadcasterAPI" ( falling back to the prim name if absent.""" ) - uniform double ros:joint_state_broadcaster:publish_rate ( - customData = { - string apiName = "publishRate" - } - doc = """Frequency in Hz at which joint states are published.""" - ) - - uniform string ros:joint_state_broadcaster:frame_id ( - customData = { - string apiName = "frameId" - } - doc = """The TF frame_id to be used in the published JointState - messages.""" - ) } diff --git a/rep.md b/rep.md index 5176ed0..90414d1 100644 --- a/rep.md +++ b/rep.md @@ -23,7 +23,6 @@ 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 @@ -239,8 +238,6 @@ 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 Prohibited Interfaces Simulator-level interfaces are prohibited in assets to avoid clashes, including: @@ -255,7 +252,6 @@ Number of concepts in ROS (e.g. robot descriptions, controllers) rely on joints 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 ``). If this property is missing, simulators must fall back to using the prim name. ->>>>>>> 84b460b (Added `ros2:joint:name` custom attribute instead of ROS2JointAPI schema.) ## 3. Export and Conversion diff --git a/schema/schema.usda b/schema/schema.usda index 75e488c..6ee03c6 100644 --- a/schema/schema.usda +++ b/schema/schema.usda @@ -342,359 +342,3 @@ class "RosFrameAPI" ( USD TimeSamples), the simulator broadcasts to /tf.""" ) } - -# ====================================================================== -# Section 4 - Robot Control -# -# Two approaches to simulating a robotic system are defined: -# -# Control-level simulation (Section 4.1): -# The simulator exposes joint state and command interfaces to an -# external control algorithm. The interface shape is simulator- -# specific (e.g. ros2_control hardware_interface, IPC, HIL). -# Prims are marked with RosExternalControlAPI as a built-in. -# -# Application-level (integrated) simulation (Section 4.2): -# The controller runs inside the simulator and is configured via -# prim parameters and ROS communication. Prims are marked with -# RosIntegratedControlAPI as a built-in and reference topic, -# service, or action interface prims. -# ====================================================================== - -# ====================================================================== -# Section 4.1 - RosExternalControlAPI -# ====================================================================== - -class "RosExternalControlAPI" ( - inherits = - customData = { - token apiSchemaType = "singleApply" - string className = "ExternalControlAPI" - } - doc = """Base schema for exposing robot control interfaces to external control algorithms. - - Applied (via 'prepend apiSchemas') by simulator-specific schemas to - identify prims whose joint state and command interfaces should be - exposed to an external control entity (e.g. a ros2_control - hardware_interface plugin, an inter-process controller, or a - hardware-in-the-loop connection). - """ -) -{ -} - -# ====================================================================== -# Section 4.2 - RosIntegratedControlAPI -# ====================================================================== - -class "RosIntegratedControlAPI" ( - inherits = - customData = { - token apiSchemaType = "singleApply" - string className = "IntegratedControlAPI" - } - doc = """Base schema for integrated (application-level) robot controllers. - - Included as a built-in via 'prepend apiSchemas' by simulator-specific - or standardized controller schemas that run the controller logic - inside the simulator. All prims referenced by a controller that - inherits this schema must have at least one of RosTopicAPI, - RosServiceAPI, or RosActionAPI applied. USD does not enforce this - constraint at the schema level; simulators are responsible for - runtime validation. - """ -) -{ -} - -# ====================================================================== -# Section 4.2.1.1 - RosRigidBodyTwistControllerAPI -# ====================================================================== - -class "RosRigidBodyTwistControllerAPI" ( - inherits = - prepend apiSchemas = ["RosIntegratedControlAPI"] - customData = { - token apiSchemaType = "singleApply" - string className = "RigidBodyTwistControllerAPI" - } - doc = """Controls a rigid body via geometry_msgs/Twist messages. - - Subscribes to a Twist topic and applies the commanded linear and - angular velocities directly to a rigid body in the physics engine, - with optional velocity and acceleration limits. Implementation should - follow logic similar to the diff_drive_controller in ros2_controllers. - """ -) -{ - rel ros:rigid_body_twist:subscriber ( - customData = { - string apiName = "subscriber" - } - doc = """Reference to a prim with RosTopicAPI configured as a - subscription for geometry_msgs/Twist control messages.""" - ) - - rel ros:rigid_body_twist:body ( - customData = { - string apiName = "body" - } - doc = """Reference to a prim with UsdPhysicsRigidBodyAPI to which - the commanded velocities are applied.""" - ) - - uniform double ros:rigid_body_twist:cmd_vel_timeout = 0.5 ( - customData = { - string apiName = "cmdVelTimeout" - } - doc = """Timeout in seconds after which a velocity command is - considered stale and the body velocity is zeroed.""" - ) - - uniform double ros:rigid_body_twist:linear:x:max_velocity ( - customData = { - string apiName = "linearXMaxVelocity" - } - doc = """Maximum linear velocity along the X axis in m/s.""" - ) - - uniform double ros:rigid_body_twist:linear:x:max_acceleration ( - customData = { - string apiName = "linearXMaxAcceleration" - } - doc = """Maximum linear acceleration along the X axis in m/s².""" - ) - - uniform double ros:rigid_body_twist:angular:z:max_velocity ( - customData = { - string apiName = "angularZMaxVelocity" - } - doc = """Maximum angular velocity around the Z axis in rad/s.""" - ) - - uniform double ros:rigid_body_twist:angular:z:max_acceleration ( - customData = { - string apiName = "angularZMaxAcceleration" - } - doc = """Maximum angular acceleration around the Z axis in rad/s².""" - ) -} - -# ====================================================================== -# Section 4.2.1.2 - RosDiffDriveControllerAPI -# ====================================================================== - -class "RosDiffDriveControllerAPI" ( - inherits = - prepend apiSchemas = ["RosIntegratedControlAPI"] - customData = { - token apiSchemaType = "singleApply" - string className = "DiffDriveControllerAPI" - } - doc = """Controls a differential drive robot via geometry_msgs/Twist messages. - - Subscribes to a Twist topic, converts commanded linear and angular - velocities into individual wheel velocities, and applies them to - wheel joint prims with UsdPhysicsDriveAPI. Publishes odometry data - as nav_msgs/Odometry. Implementation should follow logic similar to - the diff_drive_controller in ros2_controllers. - """ -) -{ - rel ros:diff_drive:subscriber ( - customData = { - string apiName = "subscriber" - } - doc = """Reference to a prim with RosTopicAPI configured as a - subscription for geometry_msgs/Twist velocity commands.""" - ) - - rel ros:diff_drive:odom ( - customData = { - string apiName = "odom" - } - doc = """Reference to a prim with RosTopicAPI configured as a - publisher for nav_msgs/Odometry data.""" - ) - - rel ros:diff_drive:left_wheels ( - customData = { - string apiName = "leftWheels" - } - doc = """References to prims with UsdPhysicsDriveAPI representing - the left wheel joints.""" - ) - - rel ros:diff_drive:right_wheels ( - customData = { - string apiName = "rightWheels" - } - doc = """References to prims with UsdPhysicsDriveAPI representing - the right wheel joints.""" - ) - - uniform double ros:diff_drive:wheel_separation ( - customData = { - string apiName = "wheelSeparation" - } - doc = """Distance between the left and right wheel contact points - in meters.""" - ) - - uniform double ros:diff_drive:wheel_radius ( - customData = { - string apiName = "wheelRadius" - } - doc = """Radius of the wheels in meters.""" - ) - - uniform double ros:diff_drive:cmd_vel_timeout = 0.5 ( - customData = { - string apiName = "cmdVelTimeout" - } - doc = """Timeout in seconds after which a velocity command is - considered stale and wheel velocities are zeroed.""" - ) - - uniform double ros:diff_drive:linear:x:max_velocity ( - customData = { - string apiName = "linearXMaxVelocity" - } - doc = """Maximum linear velocity along the X axis in m/s.""" - ) - - uniform double ros:diff_drive:linear:x:max_acceleration ( - customData = { - string apiName = "linearXMaxAcceleration" - } - doc = """Maximum linear acceleration along the X axis in m/s².""" - ) - - uniform double ros:diff_drive:angular:z:max_velocity ( - customData = { - string apiName = "angularZMaxVelocity" - } - doc = """Maximum angular velocity around the Z axis in rad/s.""" - ) - - uniform double ros:diff_drive:angular:z:max_acceleration ( - customData = { - string apiName = "angularZMaxAcceleration" - } - doc = """Maximum angular acceleration around the Z axis in rad/s².""" - ) -} - -# ====================================================================== -# Section 4.2.1.3 - RosJointTrajectoryControllerAPI -# ====================================================================== - -class "RosJointTrajectoryControllerAPI" ( - inherits = - prepend apiSchemas = ["RosIntegratedControlAPI"] - customData = { - token apiSchemaType = "singleApply" - string className = "JointTrajectoryControllerAPI" - } - doc = """Executes joint trajectories via control_msgs/FollowJointTrajectory actions. - - Accepts action goals and commands the simulator to follow the - specified joint trajectory. Implementation should follow logic - similar to the joint_trajectory_controller in ros2_controllers. - """ -) -{ - rel ros:joint_trajectory:server ( - customData = { - string apiName = "server" - } - doc = """Reference to a prim with RosActionAPI configured as a - server for control_msgs/FollowJointTrajectory action goals.""" - ) - - rel ros:joint_trajectory:command_joints ( - customData = { - string apiName = "commandJoints" - } - doc = """References to prims with UsdPhysicsJoint representing - the joints to be commanded along the trajectory. Simulators must - use the ros:joint:name custom property for joint name mapping, - falling back to the prim name if absent.""" - ) - - uniform double ros:joint_trajectory:action_monitor_rate ( - customData = { - string apiName = "actionMonitorRate" - } - doc = """Frequency in Hz at which trajectory execution progress - is monitored.""" - ) - - uniform double ros:joint_trajectory:stopped_velocity_tolerance ( - customData = { - string apiName = "stoppedVelocityTolerance" - } - doc = """Velocity tolerance at the end of the trajectory below - which the controlled system is considered stopped.""" - ) - - uniform double ros:joint_trajectory:timeout ( - customData = { - string apiName = "timeout" - } - doc = """Maximum time in seconds allowed to reach the trajectory - goal before the action is aborted.""" - ) -} - -# ====================================================================== -# Section 4.2.1.4 - RosJointStateBroadcasterAPI -# ====================================================================== - -class "RosJointStateBroadcasterAPI" ( - inherits = - prepend apiSchemas = ["RosIntegratedControlAPI"] - customData = { - token apiSchemaType = "singleApply" - string className = "JointStateBroadcasterAPI" - } - doc = """Reads joint states and publishes them as sensor_msgs/JointState messages. - - Implementation should follow logic similar to the - joint_state_broadcaster in ros2_controllers. - """ -) -{ - rel ros:joint_state_broadcaster:publisher ( - customData = { - string apiName = "publisher" - } - doc = """Reference to a prim with RosTopicAPI configured as a - publisher for sensor_msgs/JointState messages.""" - ) - - rel ros:joint_state_broadcaster:joints ( - customData = { - string apiName = "joints" - } - doc = """References to prims with UsdPhysicsJoint representing - the joints whose states are to be broadcast. Simulators must use - the ros:joint:name custom property for joint name mapping, - falling back to the prim name if absent.""" - ) - - uniform double ros:joint_state_broadcaster:publish_rate ( - customData = { - string apiName = "publishRate" - } - doc = """Frequency in Hz at which joint states are published.""" - ) - - uniform string ros:joint_state_broadcaster:frame_id ( - customData = { - string apiName = "frameId" - } - doc = """The TF frame_id to be used in the published JointState - messages.""" - ) -} From b74b53563f46fa19f0b09ad6cd53169bd330761f Mon Sep 17 00:00:00 2001 From: Ayush Ghosh Date: Tue, 31 Mar 2026 22:46:11 -0700 Subject: [PATCH 072/111] Added namespace concatenation rules Signed-off-by: Adam Dabrowski --- rep.md | 23 ++++++++++++++++++++++- 1 file changed, 22 insertions(+), 1 deletion(-) diff --git a/rep.md b/rep.md index 90414d1..3e058c0 100644 --- a/rep.md +++ b/rep.md @@ -172,10 +172,31 @@ Neither OpenUSD nor glTF 2.0 currently standardize the specification of ROS inte ### 2.1 The ROS Context (`RosContextAPI`) The root prim of a ROS-interfaced simulation asset may define its context namespace. -* `string ros:context:namespace`: Prefixes all topics within this scope (e.g., `/robot_1`). The namespace is additive in the asset hierarchy and with a top-level namespace set during simulation deployment (e.g., via the `SpawnEntity` service). +* `string ros:context:namespace`: Prefixes all topics within this scope (e.g., `/robot_1`). Multiple values across the hierarchy are concatenated. See Section 2.1.1 for full rules. * `int ros:context:domain_id` (Optional): Overrides the default ROS Domain ID for interfaces descending from this context. * `string ros:context:parent_frame` (Optional, Default: `"world"`): Defines the parent `frame_id` used when the simulator broadcasts the ground-truth transform of this context's root prim. It is only valid for the top-most context in the resolved USD Stage and ignored otherwise. +#### 2.1.1 Hierarchical Namespace Concatenation + +`RosContextAPI` may be applied at multiple levels of the USD hierarchy; not necessarily just the robot's root prim. This enables per-sensor and per-module sub-namespacing within a single asset without manual per-interface configuration. + +Simulators must concatenate all `ros:context:namespace` values found on an interface prim's ancestor chain (in top-down order, from the stage root to the interface prim itself) to form the fully-resolved namespace for that interface: +* Each non-empty `ros:context:namespace` segment contributes one path component. Simulators must insert a `/` separator between segments and normalize the result (e.g., segments `"robot_1"` and `"left_camera"` produce the namespace `/robot_1/left_camera`). +* An absent or empty-string `ros:context:namespace` contributes no segment. +* Any runtime namespace injected at deployment time (e.g., via the `/spawn_entity` service's `entity_namespace` field) is prepended as the outermost segment, before any namespace authored in the USD file. + +**TF topic names:** TF frames for all joints and links within one robot must be published on a single, robot-level topic. The `/tf` and `/tf_static` topic names are scoped using **only** the namespace from the outermost `RosContextAPI` ancestor of the robot's root prim. Sub-namespace segments from deeper `RosContextAPI` prims must not be appended to the TF topic name. TF frame IDs within the tree are unaffected by sub-namespace authoring. + +**Multi-robot deployment:** When the same asset is instantiated more than once in a stage (e.g., a fleet of identical mobile robots), each instance's root prim must carry a unique `ros:context:namespace` value. The recommended convention is to use the instance's stage prim name (e.g., `robot_1`, `robot_2`). This isolates all ROS topics and TF trees per robot without modifying the source USD file, enabling tooling to duplicate assets and update only the root namespace attribute. + +**Intra-robot asset composition:** When a robot is assembled from modular sub-assets (e.g., `arm.usd`, `mobile_base.usd`, `lidar_module.usd` referenced into `robot.usd` per Section 1.2.1), each sub-asset should author a default `ros:context:namespace` on its root prim. This serves two purposes: + +1. **Standalone operation:** The sub-asset can be loaded and tested in isolation with its interfaces already namespaced without collision. +2. **Automatic scoping when composed:** When the sub-asset is referenced under a parent prim that also bears `RosContextAPI`, the concatenation rule produces a fully scoped topic without any additional configuration. + +**Duplicate sub-assets:** When the same sub-asset is referenced more than once into the same robot (e.g., a stereo camera pair both referencing `camera_module.usd`, or two identical finger modules), the composing `robot.usd` must override the `ros:context:namespace` attribute on each reference's root prim via a local USD opinion to give each instance a distinct name. Without this override, both instances publish to identical topic names and collide. The source sub-asset should author a generic placeholder namespace (e.g., `"camera"`) that the composing layer overrides per instance (e.g., `"camera_left"`, `"camera_right"`). As local opinions are the strongest strength in the LIVRPS order, this override does not require modifying the source file. + + ### 2.2 Interface Placement ROS interface schemas (`RosTopicAPI`, `RosServiceAPI`, `RosActionAPI`) must be applied to prims according to these placement rules: From b864bef858f198e7e6bcb5fb9c4782669bc0744b Mon Sep 17 00:00:00 2001 From: Ayush Ghosh Date: Wed, 1 Apr 2026 19:07:43 -0700 Subject: [PATCH 073/111] Added changes from feedback Signed-off-by: Adam Dabrowski --- rep.md | 36 +++++++++++++++++++++++++++++++----- 1 file changed, 31 insertions(+), 5 deletions(-) diff --git a/rep.md b/rep.md index 3e058c0..341d982 100644 --- a/rep.md +++ b/rep.md @@ -87,7 +87,7 @@ As illustrated in Figure 1, assets should be divided into functional layers comp To guarantee that simulation assets remain self-contained, portable, and predictable across different simulator parsers, asset authors must adhere to the following constraints regarding OpenUSD's LIVRPS composition arcs: * **[L] Local:** Primary authoring of overrides and properties on the asset is fully supported. * **[I] Inherits & [S] Specializes:** Asset authors should not rely on `Inherits` or `Specializes` arcs that target class definitions outside the asset's own layer stack for core robot kinematics, physics APIs, or ROS schemas when distributing standalone assets. These arcs create hard dependencies on external class hierarchies; if a simulator's environment lacks the base class definitions, the asset will fail to parse correctly. The inherits-instanceable pattern, where the class prim is defined within the same asset, remains valid and is recommended for applying uniform overrides across instances. -* **[V] VariantSets:** Permitted and encouraged for asset reusability (see Section 1.2.3). +* **[V] VariantSets:** Permitted and encouraged for asset reusability (see Section 1.2.4). * **[R] References:** Permitted for logical assembly (e.g., composing a robot by referencing an independent `arm.usd` and `base.usd`). * **[P] Payloads (The Payload Pattern):** Heavy data (high-resolution meshes, point clouds, large textures) must be referenced via Payloads rather than standard References. * Payloads must not gate joint or link prims themselves. The kinematic topology (Prims bearing `PhysicsRigidBodyAPI`, `PhysicsJoint` schemas, and `Ros*API` schemas) must reside in the primarily loaded scene graph (e.g., via Local authoring or standard References). @@ -172,7 +172,7 @@ Neither OpenUSD nor glTF 2.0 currently standardize the specification of ROS inte ### 2.1 The ROS Context (`RosContextAPI`) The root prim of a ROS-interfaced simulation asset may define its context namespace. -* `string ros:context:namespace`: Prefixes all topics within this scope (e.g., `/robot_1`). Multiple values across the hierarchy are concatenated. See Section 2.1.1 for full rules. +* `string ros:context:namespace`: Prefixes all topics within this scope (e.g., `robot_1`). Multiple values across the hierarchy are concatenated in top-down order. See Section 2.1.1 for full rules. * `int ros:context:domain_id` (Optional): Overrides the default ROS Domain ID for interfaces descending from this context. * `string ros:context:parent_frame` (Optional, Default: `"world"`): Defines the parent `frame_id` used when the simulator broadcasts the ground-truth transform of this context's root prim. It is only valid for the top-most context in the resolved USD Stage and ignored otherwise. @@ -181,7 +181,7 @@ The root prim of a ROS-interfaced simulation asset may define its context namesp `RosContextAPI` may be applied at multiple levels of the USD hierarchy; not necessarily just the robot's root prim. This enables per-sensor and per-module sub-namespacing within a single asset without manual per-interface configuration. Simulators must concatenate all `ros:context:namespace` values found on an interface prim's ancestor chain (in top-down order, from the stage root to the interface prim itself) to form the fully-resolved namespace for that interface: -* Each non-empty `ros:context:namespace` segment contributes one path component. Simulators must insert a `/` separator between segments and normalize the result (e.g., segments `"robot_1"` and `"left_camera"` produce the namespace `/robot_1/left_camera`). +* Each non-empty `ros:context:namespace` segment contributes one path component and must be authored as a bare name with no leading or trailing `/`. Simulators must insert a `/` separator between segments and normalize the result (e.g., segments `"robot_1"` and `"left_camera"` produce the namespace `/robot_1/left_camera`). * An absent or empty-string `ros:context:namespace` contributes no segment. * Any runtime namespace injected at deployment time (e.g., via the `/spawn_entity` service's `entity_namespace` field) is prepended as the outermost segment, before any namespace authored in the USD file. @@ -189,12 +189,38 @@ Simulators must concatenate all `ros:context:namespace` values found on an inter **Multi-robot deployment:** When the same asset is instantiated more than once in a stage (e.g., a fleet of identical mobile robots), each instance's root prim must carry a unique `ros:context:namespace` value. The recommended convention is to use the instance's stage prim name (e.g., `robot_1`, `robot_2`). This isolates all ROS topics and TF trees per robot without modifying the source USD file, enabling tooling to duplicate assets and update only the root namespace attribute. -**Intra-robot asset composition:** When a robot is assembled from modular sub-assets (e.g., `arm.usd`, `mobile_base.usd`, `lidar_module.usd` referenced into `robot.usd` per Section 1.2.1), each sub-asset should author a default `ros:context:namespace` on its root prim. This serves two purposes: +**Intra-robot asset composition:** When a robot is assembled from modular sub-assets (e.g., `arm.usd`, `mobile_base.usd`, `lidar_module.usd` referenced into `robot.usd` per Section 1.2.1), each sub-asset should author a default `ros:context:namespace` on its `defaultPrim`, consistent with the USD reference-payload entry-point pattern. This serves two purposes: 1. **Standalone operation:** The sub-asset can be loaded and tested in isolation with its interfaces already namespaced without collision. 2. **Automatic scoping when composed:** When the sub-asset is referenced under a parent prim that also bears `RosContextAPI`, the concatenation rule produces a fully scoped topic without any additional configuration. -**Duplicate sub-assets:** When the same sub-asset is referenced more than once into the same robot (e.g., a stereo camera pair both referencing `camera_module.usd`, or two identical finger modules), the composing `robot.usd` must override the `ros:context:namespace` attribute on each reference's root prim via a local USD opinion to give each instance a distinct name. Without this override, both instances publish to identical topic names and collide. The source sub-asset should author a generic placeholder namespace (e.g., `"camera"`) that the composing layer overrides per instance (e.g., `"camera_left"`, `"camera_right"`). As local opinions are the strongest strength in the LIVRPS order, this override does not require modifying the source file. +**Duplicate sub-assets:** When the same sub-asset is referenced more than once into the same robot (e.g., a stereo camera pair both referencing `camera_module.usd`, or two identical finger modules), the composing `robot.usd` must override the `ros:context:namespace` attribute on each reference's root prim via a local USD opinion to give each instance a distinct name. Without this override, both instances publish to identical topic names and collide. The source sub-asset should author a generic placeholder namespace (e.g., `"camera"`) that the composing layer overrides per instance (e.g., `"camera_left"`, `"camera_right"`). As local opinions are the strongest strength in the LIVRPS order, this override does not require modifying the source file. For example: + +``` +def Xform "robot" ( + prepend apiSchemas = ["RosContextAPI"] +) { + string ros:context:namespace = "robot_1" + + def Xform "camera_left" ( + references = @./camera_module.usd@ + prepend apiSchemas = ["RosContextAPI"] + ) { + string ros:context:namespace = "camera_left" # overrides "camera" from source + } + + def Xform "camera_right" ( + references = @./camera_module.usd@ + prepend apiSchemas = ["RosContextAPI"] + ) { + string ros:context:namespace = "camera_right" + } +} +``` + +**Instancing caveat:** When a sub-asset is referenced with `instanceable = true`, attributes on the reference root prim remain editable, while its children become instance proxies meaning their attributes cannot be changed. A `ros:context:namespace` override cannot be defined in an instance proxy and must be authored on the reference root prim itself, or lofted above the payload boundary. + +*Note: `RosContextAPI` prims are part of the lightweight interface graph and must remain traversable without loading geometry payloads (see Section 2.2).* ### 2.2 Interface Placement From a1c90fa5de74dd5f45776094004ad62525345e2d Mon Sep 17 00:00:00 2001 From: Ayush Ghosh <149644562+ayushgnv@users.noreply.github.com> Date: Mon, 6 Apr 2026 00:09:59 -0700 Subject: [PATCH 074/111] Update rep.md Co-authored-by: Jan Hanca Signed-off-by: Adam Dabrowski --- rep.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rep.md b/rep.md index 341d982..8b3907a 100644 --- a/rep.md +++ b/rep.md @@ -213,7 +213,7 @@ def Xform "robot" ( references = @./camera_module.usd@ prepend apiSchemas = ["RosContextAPI"] ) { - string ros:context:namespace = "camera_right" + string ros:context:namespace = "camera_right" # overrides "camera" from source } } ``` From 1ff558fc90b25740d3ef2e0ab00e63073113ca41 Mon Sep 17 00:00:00 2001 From: Ayush Ghosh Date: Thu, 9 Apr 2026 12:28:34 -0700 Subject: [PATCH 075/111] Feedback changes Signed-off-by: Adam Dabrowski --- rep.md | 27 ++++++++++++--------------- 1 file changed, 12 insertions(+), 15 deletions(-) diff --git a/rep.md b/rep.md index 8b3907a..ac4929b 100644 --- a/rep.md +++ b/rep.md @@ -59,7 +59,7 @@ This REP adopts the ASWF Guidelines for Structuring USD Assets. #### 1.2.1 Schema Isolation and Functional Layering (The ETL Pipeline) -To avoid "Unknown Schema" errors in standard 3D authoring tools (e.g., Blender, Maya) and to ensure assets remain modular, functional layering (Extract-Transform-Load) should be utilized for ROS interfaces, physics, and simulator-specific tooling syntax. +To avoid "Unknown Schema" errors in standard 3D authoring tools (e.g., Blender, Maya) and to ensure assets remain modular, functional layering (Extract-Transform-Load) should be utilized for ROS interfaces, physics, and simulator-specific tooling syntax. This REP endorses the ETL composition architecture developed collaboratively by NVIDIA, Intrinsic, and Disney Research for OpenUSD robotics assets. @@ -178,23 +178,20 @@ The root prim of a ROS-interfaced simulation asset may define its context namesp #### 2.1.1 Hierarchical Namespace Concatenation -`RosContextAPI` may be applied at multiple levels of the USD hierarchy; not necessarily just the robot's root prim. This enables per-sensor and per-module sub-namespacing within a single asset without manual per-interface configuration. +The effective namespace is the top-down concatenation of `ros:context:namespace` attributes along the ancestor chain, automatically joined by `/` (e.g., `"robot_1"` and `"left_camera"` produce `/robot_1/left_camera`). An absent or empty attribute contributes no segment. Segments follow two authoring modes: +* **Composable (default):** A bare name with no leading or trailing `/` and no runtime substitutions (`~`, `{}`). +* **Absolute:** A leading `/` resets the chain, ignoring all ancestor values. -Simulators must concatenate all `ros:context:namespace` values found on an interface prim's ancestor chain (in top-down order, from the stage root to the interface prim itself) to form the fully-resolved namespace for that interface: -* Each non-empty `ros:context:namespace` segment contributes one path component and must be authored as a bare name with no leading or trailing `/`. Simulators must insert a `/` separator between segments and normalize the result (e.g., segments `"robot_1"` and `"left_camera"` produce the namespace `/robot_1/left_camera`). -* An absent or empty-string `ros:context:namespace` contributes no segment. -* Any runtime namespace injected at deployment time (e.g., via the `/spawn_entity` service's `entity_namespace` field) is prepended as the outermost segment, before any namespace authored in the USD file. +`ros:context:domain_id` is resolved from the nearest ancestor `RosContextAPI` prim; the simulator's default applies if none is set. `ros:context:parent_frame` is only valid on the outermost `RosContextAPI` in the stage and must be ignored on nested contexts. -**TF topic names:** TF frames for all joints and links within one robot must be published on a single, robot-level topic. The `/tf` and `/tf_static` topic names are scoped using **only** the namespace from the outermost `RosContextAPI` ancestor of the robot's root prim. Sub-namespace segments from deeper `RosContextAPI` prims must not be appended to the TF topic name. TF frame IDs within the tree are unaffected by sub-namespace authoring. +TF frames for all joints and links within one robot must be published on a single `/tf` and `/tf_static` topic, scoped using only the outermost `RosContextAPI` namespace. Sub-namespace segments must not be appended to the TF topic name. -**Multi-robot deployment:** When the same asset is instantiated more than once in a stage (e.g., a fleet of identical mobile robots), each instance's root prim must carry a unique `ros:context:namespace` value. The recommended convention is to use the instance's stage prim name (e.g., `robot_1`, `robot_2`). This isolates all ROS topics and TF trees per robot without modifying the source USD file, enabling tooling to duplicate assets and update only the root namespace attribute. +Each robot instance must carry a unique `ros:context:namespace` on its root prim; authors should use the stage prim name (e.g., `robot_1`, `robot_2`). -**Intra-robot asset composition:** When a robot is assembled from modular sub-assets (e.g., `arm.usd`, `mobile_base.usd`, `lidar_module.usd` referenced into `robot.usd` per Section 1.2.1), each sub-asset should author a default `ros:context:namespace` on its `defaultPrim`, consistent with the USD reference-payload entry-point pattern. This serves two purposes: +A modular asset's root namespace must be authored on its `defaultPrim`. When referencing that asset elsewhere, namespace overrides must be placed on the entry-point prim containing the composition arc to preserve `instanceable = true` compatibility. For duplicate sub-assets, each reference's entry-point prim must carry a distinct namespace via a local opinion — no source file modification is required. For example: -1. **Standalone operation:** The sub-asset can be loaded and tested in isolation with its interfaces already namespaced without collision. -2. **Automatic scoping when composed:** When the sub-asset is referenced under a parent prim that also bears `RosContextAPI`, the concatenation rule produces a fully scoped topic without any additional configuration. - -**Duplicate sub-assets:** When the same sub-asset is referenced more than once into the same robot (e.g., a stereo camera pair both referencing `camera_module.usd`, or two identical finger modules), the composing `robot.usd` must override the `ros:context:namespace` attribute on each reference's root prim via a local USD opinion to give each instance a distinct name. Without this override, both instances publish to identical topic names and collide. The source sub-asset should author a generic placeholder namespace (e.g., `"camera"`) that the composing layer overrides per instance (e.g., `"camera_left"`, `"camera_right"`). As local opinions are the strongest strength in the LIVRPS order, this override does not require modifying the source file. For example: +

+Example: Overriding namespace on duplicate sub-asset references ``` def Xform "robot" ( @@ -218,9 +215,9 @@ def Xform "robot" ( } ``` -**Instancing caveat:** When a sub-asset is referenced with `instanceable = true`, attributes on the reference root prim remain editable, while its children become instance proxies meaning their attributes cannot be changed. A `ros:context:namespace` override cannot be defined in an instance proxy and must be authored on the reference root prim itself, or lofted above the payload boundary. +
-*Note: `RosContextAPI` prims are part of the lightweight interface graph and must remain traversable without loading geometry payloads (see Section 2.2).* +`RosContextAPI` prims must reside outside Payload arcs so the namespace graph can be resolved without loading heavy geometry (see Section 2.2). Sub-assets intended for per-instance namespace override should not set `instanceable = true`, as descendant prims become instance proxies whose attributes cannot be overridden; any override must be authored on the reference root prim or an ancestor outside the Payload arc. ### 2.2 Interface Placement From 5d38c72097452550368bd579934d994c9aa8c8ef Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Tue, 14 Apr 2026 10:37:59 +0200 Subject: [PATCH 076/111] Added MP as author After PR #10 merge Signed-off-by: Adam Dabrowski --- rep.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rep.md b/rep.md index ac4929b..0e428a5 100644 --- a/rep.md +++ b/rep.md @@ -4,7 +4,7 @@ | :--- | :--- | | **REP** | XXXX | | **Title** | OpenUSD Conventions for Simulation Asset Interoperability | -| **Authors** | Adam Dabrowski, Mateusz Zak (Robotec.ai), Ayush Ghosh (NVIDIA) | +| **Authors** | Adam Dabrowski, Mateusz Zak, Michal Pelka (Robotec.ai), Ayush Ghosh (NVIDIA) | | **Status** | Draft | | **Type** | Standards Track | | **Content-Type** | text/markdown | From 80aa7c9d30489a98f2dd68649835437e118b688a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Tue, 14 Apr 2026 14:06:48 +0200 Subject: [PATCH 077/111] Core + extension schemas Include general schema rules for sensors and control Signed-off-by: Adam Dabrowski --- rep.md | 44 ++++++++++++++++++++++++++++++++++++-------- 1 file changed, 36 insertions(+), 8 deletions(-) diff --git a/rep.md b/rep.md index 0e428a5..b97f318 100644 --- a/rep.md +++ b/rep.md @@ -24,6 +24,8 @@ To achieve this, the specification addresses four key areas: * **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. +Following the OpenUSD and glTF 2.0 model, this REP establishes a Core Standard, and proposes general rules for handling of extension schemas, including for control interfaces and sensor simulation. + ## Motivation The ROS ecosystem chiefly relies on URDF and SDF for describing robots and environments. These formats are almost entirely confined to the ROS and Gazebo ecosystems. OpenUSD has emerged as an industry standard supported by a multitude of tools and allows artists to collaborate with simulation engineers without problematic conversions between a variety of 3D and XML formats. Ensuring OpenUSD works well with ROS integrations across robotics simulators will increase ecosystem interoperability and strengthen ROS's position in physical AI workflows such as synthetic data and generative pipelines. OpenUSD is a powerful format with an extensible architecture allowing it to capture all the semantics of other popular formats. @@ -289,7 +291,6 @@ Simulator-level interfaces are prohibited in assets to avoid clashes, including: * `/clock` topic (`rosgraph_msgs/msg/Clock` interface) for simulation time. * Any interfaces included in the `simulation_interfaces` package (e.g. spawning, simulation control). -======= ### 2.10 Custom names to ROS joints. Number of concepts in ROS (e.g. robot descriptions, controllers) rely on joints names. @@ -297,6 +298,27 @@ To ensure that joints are correctly identified and mapped to said concepts, the 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 ``). If this property is missing, simulators must fall back to using the prim name. +### 2.11 Extension Schemas + +Additional schemas are to be defined through extensions, chiefly for sensors and controls. They must follow these general rules: + +* **Use of Native Schemas:** Schema definitions must leverage core OpenUSD primitives to prevent attribute duplication. For example, `SensorCameraAPI` must apply to a `UsdGeomCamera` to append digital hardware metadata while natively reusing its optical properties. If no native analogue exists, schemas must be applied to a standard `UsdGeomXform`. +* **Separation of Transport:** Extension schemas must define purely physical or computational parameters (e.g., ray counts, wheel radius). They must not include metadata to handle ROS communication (e.g., topic names, QoS). Extension schemas should utilize relationships to target distinct transport prims (e.g., `RosTopicAPI`) to expose their data or commands. + +#### 2.11.1 Control Schemas + +In addition to extension schema rules, control interfaces and controllers must follow these rules: +* **Explicit Targeting:** Controllers must reside on dedicated logical prims (e.g., `/Robot/Controllers`) and explicitly target their actuated mechanisms. Simulators must not rely on Xform scene graph nesting to infer a controller's scope. Controllers must declare targets using OpenUSD relationships (`rel`) or standard `UsdCollectionAPI` collections. This guarantees modularity and robust path resolution when sub-assemblies are composed. +* **Actuation via Physics:** Control schemas must interface with dynamic bodies strictly through the simulation's physics pipeline. Position, velocity, and effort targets must be routed through normative OpenUSD dynamics paradigms (e.g., `UsdPhysicsDriveAPI` or solver force buffers). Controllers that directly manipulate spatial transforms must only actuate prims where `physics:kinematicEnabled = true`. Control schemas must not handle simulator-level state changes (e.g., native simulator state APIs or ROS `simulation_interfaces`), including resets for RL training or entity state manipulation. +* **Runtime selection:** A single asset may contain multiple, mutually exclusive control paradigms for the same hardware (e.g., trajectory control vs. direct effort control). While `VariantSets` remain the standard for structural hardware changes, control schemas must provide a dynamic enablement mechanism (e.g., `bool control:enabled`) to support runtime switching. The asset's default authored state must guarantee that overlapping controllers are not simultaneously active. + +#### 2.11.2 Sensor Schemas + +In addition to extension schema rules, sensor schemas must follow these rules: +* **Ground Truth:** Sensor schemas must emulate measurable phenomena to ensure valid Software-in-the-Loop (SiL) testing. Simulator-generated Ground Truth artifacts (e.g., semantic segmentations, bounding boxes) must not be bundled into physical sensor schemas; they should be explicitly requested via dedicated annotator schemas. +* **Traversal:** Sensor schemas must be applied directly to the `UsdGeomXform` or `UsdGeomCamera` defining their physical origin and local coordinate frame. To ensure efficient parser discovery, these prims must reside in the asset's lightweight, traversable kinematic hierarchy. +* **Graceful Degradation:** Sensor schemas must define a functional, universal baseline of parameters. Advanced, engine-specific behaviors (e.g., proprietary rendering profiles, custom noise models) must be authored exclusively via vendor-namespaced custom attributes (e.g., `isaac:`, `gazebo:`). Simulators must safely ignore unrecognized namespaces and gracefully fall back to the universal baseline. + ## 3. Export and Conversion OpenUSD is a vast standard supporting complex features. To guarantee that assets can be converted to glTF 2.0 and successfully exported to lightweight applications, assets must adhere to this constrained subset. @@ -349,20 +371,26 @@ 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 ``, MJCF ``). Obsolete approaches such as injecting legacy `` 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. -## Extensions - -A number of features (e.g., control interfaces, sensors specification) are proposed to extend this schema. -These extensions are not required for compliance with the core REP, but are recommended for simulators targeting interoperability with ROS. -They will be defined in future iterations of this document and shared with the community for feedback. - ## Tools -### Schema Definition +### Core Schema Definition The normative OpenUSD schema definition for all `Ros*API` schemas is provided in `schema/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. ### Compliance Checker A REP-XXXX compliance checker is to be developed and shared with the community. The tool will provide validation of all REP recommendations for OpenUSD assets and supply actionable feedback for the user for every violation or non-conformance. +## Extensions + +Due to the number and dynamic nature of control and sensor types, these will be handled as extension schemas to interoperability profile compliance. They will be submitted and ratified independently. + +A canonical repository for these extensions is `ros-simulation/openusd-schemas`, and the following is mandated: +- A submission must follow the rules of this REP where applicable, e.g. including declarative parameters that can be implemented accross simulators, and adhering to general rules for sensors and control schemas (e.g. graceful degradation). A submission may include one or more vendor or physic engine specific layers as outlined in Section 1.4. +- A submission must include addition to Compliance Checker which allows the use of new schema to be validated, a documentation of use, and a minimal example asset. + +### Compliant Assets + +A canonincal repository of open-source, compliant simulation assets is to be established as `ros-simulation/openusd-assets`. These assets will have payloads hosted independently (e.g. in a dedicated repository such as Hugging Face) and must pass the Compliance Checker. + ## References * **[NVIDIA-ETL-PIPELINE]** NVIDIA, Intrinsic, Disney Research. "Using OpenUSD for Modular and Scalable Robotic Simulation and Development". URL: `https://developer.nvidia.com/blog/using-openusd-for-modular-and-scalable-robotic-simulation-and-development/` * **[NVIDIA-ASSETS]** NVIDIA, "Content Guidelines and Requirements". URL: `https://docs.omniverse.nvidia.com/kit/docs/asset-requirements/latest/index.html` From 7bf8bdac73f694eb3319d41467fb81edabc38aa2 Mon Sep 17 00:00:00 2001 From: Adam Dabrowski Date: Tue, 14 Apr 2026 16:24:11 +0200 Subject: [PATCH 078/111] - Restructured schema extensions to a separate chapter - Fixed inconsistency in 2.2 - which helps with composability. - Minor typos fixes. Signed-off-by: Adam Dabrowski --- rep.md | 75 +++++++++++++++++++++++++++++++--------------------------- 1 file changed, 40 insertions(+), 35 deletions(-) diff --git a/rep.md b/rep.md index b97f318..da80d1f 100644 --- a/rep.md +++ b/rep.md @@ -23,6 +23,7 @@ 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** establishes the interoperability ecosystem registries for extending sensor and control schemas. Following the OpenUSD and glTF 2.0 model, this REP establishes a Core Standard, and proposes general rules for handling of extension schemas, including for control interfaces and sensor simulation. @@ -125,8 +126,8 @@ OpenUSD's native instancing mechanisms are designed for repetitive visual and st * When composed into a larger kinematic tree, the composing stage should use the OpenUSD list-edit operation `delete apiSchemas = ["PhysicsArticulationRootAPI"]` to prune nested articulation roots. This prevents reduced-coordinate physics solvers from fracturing the robot. * **Loop Closures:** Articulations must form a spanning tree. Joints that close a kinematic loop (e.g., parallel linkages, four-bar mechanisms) must set `physics:excludeFromArticulation = true`. Parsers building the kinematic tree must treat these joints as standalone maximal-coordinate constraints rather than parent-child links. * **Mass Properties:** Assets and simulators must follow `UsdPhysicsMassAPI` guidelines. Dynamic bodies must define a strictly positive mass (mass > 0). Setting mass = 0 to imply infinite/static mass violates the UsdPhysics specification, which ignores 0.0 and falls back to a computed default mass. Instead, authors must use standard mechanisms for non-dynamic bodies: - * Static Environments: Fixed props (e.g., walls, racks) must possess a PhysicsCollisionAPI but omit the PhysicsRigidBodyAPI. OpenUSD implicitly treats these as having zero velocity and infinite mass. - * Robot Anchors: A fixed robot base must have a valid mass > 0 and be anchored via a UsdPhysicsFixedJoint with an empty physics:body0 relationship (which natively represents the world). + * *Static Environments:* Fixed props (e.g., walls, racks) must possess a PhysicsCollisionAPI but omit the PhysicsRigidBodyAPI. OpenUSD implicitly treats these as having zero velocity and infinite mass. + * *Robot Anchors:* A fixed robot base must have a valid mass > 0 and be anchored via a UsdPhysicsFixedJoint with an empty physics:body0 relationship (which natively represents the world). * *Kinematic Bodies:* Moving bodies that are animated but not dynamically driven by physics should set the physics:kinematicEnabled attribute to true. * *Dummy Frames:* Non-physical dummy frames (e.g., `camera_optical_frame`) must not possess a `PhysicsRigidBodyAPI`. They should be tracked using the `RosFrameAPI` as defined in Section 2.8. * **Inertia Representation:** Unlike URDF and SDFormat's 6-value symmetric matrix, OpenUSD requires an eigendecomposed inertia tensor. Converters must mathematically decompose the source matrix into physics:diagonalInertia (eigenvalues) and physics:principalAxes (quaternion). This native decomposed form is the strict single source of truth; custom 6-value array attributes must not be authored or parsed. @@ -226,7 +227,7 @@ def Xform "robot" ( 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) should be placed at root prim of the robot assembly. +* **Robot-wide interfaces:** Aggregate interfaces spanning a kinematic tree (e.g., `JointState` publisher, `FollowJointTrajectory` server) should be decoupled from the physical rigid-body hierarchy. Authors should place them on dedicated, non-physical logical prims (e.g., `/Robot/Interfaces`) descendant from the `RosContextAPI` prim. * **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. @@ -293,32 +294,11 @@ Simulator-level interfaces are prohibited in assets to avoid clashes, including: ### 2.10 Custom names to ROS joints. -Number of concepts in ROS (e.g. robot descriptions, controllers) rely on joints names. +A number of concepts in ROS (e.g. robot descriptions, controllers) rely 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 ``). If this property is missing, simulators must fall back to using the prim name. -### 2.11 Extension Schemas - -Additional schemas are to be defined through extensions, chiefly for sensors and controls. They must follow these general rules: - -* **Use of Native Schemas:** Schema definitions must leverage core OpenUSD primitives to prevent attribute duplication. For example, `SensorCameraAPI` must apply to a `UsdGeomCamera` to append digital hardware metadata while natively reusing its optical properties. If no native analogue exists, schemas must be applied to a standard `UsdGeomXform`. -* **Separation of Transport:** Extension schemas must define purely physical or computational parameters (e.g., ray counts, wheel radius). They must not include metadata to handle ROS communication (e.g., topic names, QoS). Extension schemas should utilize relationships to target distinct transport prims (e.g., `RosTopicAPI`) to expose their data or commands. - -#### 2.11.1 Control Schemas - -In addition to extension schema rules, control interfaces and controllers must follow these rules: -* **Explicit Targeting:** Controllers must reside on dedicated logical prims (e.g., `/Robot/Controllers`) and explicitly target their actuated mechanisms. Simulators must not rely on Xform scene graph nesting to infer a controller's scope. Controllers must declare targets using OpenUSD relationships (`rel`) or standard `UsdCollectionAPI` collections. This guarantees modularity and robust path resolution when sub-assemblies are composed. -* **Actuation via Physics:** Control schemas must interface with dynamic bodies strictly through the simulation's physics pipeline. Position, velocity, and effort targets must be routed through normative OpenUSD dynamics paradigms (e.g., `UsdPhysicsDriveAPI` or solver force buffers). Controllers that directly manipulate spatial transforms must only actuate prims where `physics:kinematicEnabled = true`. Control schemas must not handle simulator-level state changes (e.g., native simulator state APIs or ROS `simulation_interfaces`), including resets for RL training or entity state manipulation. -* **Runtime selection:** A single asset may contain multiple, mutually exclusive control paradigms for the same hardware (e.g., trajectory control vs. direct effort control). While `VariantSets` remain the standard for structural hardware changes, control schemas must provide a dynamic enablement mechanism (e.g., `bool control:enabled`) to support runtime switching. The asset's default authored state must guarantee that overlapping controllers are not simultaneously active. - -#### 2.11.2 Sensor Schemas - -In addition to extension schema rules, sensor schemas must follow these rules: -* **Ground Truth:** Sensor schemas must emulate measurable phenomena to ensure valid Software-in-the-Loop (SiL) testing. Simulator-generated Ground Truth artifacts (e.g., semantic segmentations, bounding boxes) must not be bundled into physical sensor schemas; they should be explicitly requested via dedicated annotator schemas. -* **Traversal:** Sensor schemas must be applied directly to the `UsdGeomXform` or `UsdGeomCamera` defining their physical origin and local coordinate frame. To ensure efficient parser discovery, these prims must reside in the asset's lightweight, traversable kinematic hierarchy. -* **Graceful Degradation:** Sensor schemas must define a functional, universal baseline of parameters. Advanced, engine-specific behaviors (e.g., proprietary rendering profiles, custom noise models) must be authored exclusively via vendor-namespaced custom attributes (e.g., `isaac:`, `gazebo:`). Simulators must safely ignore unrecognized namespaces and gracefully fall back to the universal baseline. - ## 3. Export and Conversion OpenUSD is a vast standard supporting complex features. To guarantee that assets can be converted to glTF 2.0 and successfully exported to lightweight applications, assets must adhere to this constrained subset. @@ -371,26 +351,51 @@ 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 ``, MJCF ``). Obsolete approaches such as injecting legacy `` 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. -## Tools - -### Core Schema Definition -The normative OpenUSD schema definition for all `Ros*API` schemas is provided in `schema/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. - -### Compliance Checker -A REP-XXXX compliance checker is to be developed and shared with the community. The tool will provide validation of all REP recommendations for OpenUSD assets and supply actionable feedback for the user for every violation or non-conformance. - -## Extensions +## 4. The Interoperability Ecosystem Due to the number and dynamic nature of control and sensor types, these will be handled as extension schemas to interoperability profile compliance. They will be submitted and ratified independently. +### 4.1 Schema Registry + A canonical repository for these extensions is `ros-simulation/openusd-schemas`, and the following is mandated: - A submission must follow the rules of this REP where applicable, e.g. including declarative parameters that can be implemented accross simulators, and adhering to general rules for sensors and control schemas (e.g. graceful degradation). A submission may include one or more vendor or physic engine specific layers as outlined in Section 1.4. - A submission must include addition to Compliance Checker which allows the use of new schema to be validated, a documentation of use, and a minimal example asset. -### Compliant Assets +#### 4.1.1 General Extension Schema Rules + +Additional schemas are to be defined through extensions, chiefly for sensors and controls. They must follow these general rules: + +* **Use of Native Schemas:** Schema definitions must leverage core OpenUSD primitives to prevent attribute duplication. For example, `SensorCameraAPI` must apply to a `UsdGeomCamera` to append digital hardware metadata while natively reusing its optical properties. If no native analogue exists, schemas must be applied to a standard `UsdGeomXform`. +* **Separation of Transport:** Extension schemas must define purely physical or computational parameters (e.g., ray counts, wheel radius). They must not include metadata to handle ROS communication (e.g., topic names, QoS). Extension schemas should utilize relationships to target distinct transport prims (e.g., `RosTopicAPI`) to expose their data or commands. + +#### 4.1.2 Control Schemas + +In addition to general extension schema rules, control interfaces and controllers must follow these rules: +* **Explicit Targeting:** Controllers must reside on dedicated logical prims (e.g., `/Robot/Controllers`) and explicitly target their actuated mechanisms. Simulators must not rely on Xform scene graph nesting to infer a controller's scope. Controllers must declare targets using OpenUSD relationships (`rel`) or standard `UsdCollectionAPI` collections. This guarantees modularity and robust path resolution when sub-assemblies are composed. +* **Actuation via Physics:** Control schemas must interface with dynamic bodies strictly through the simulation's physics pipeline. Position, velocity, and effort targets must be routed through normative OpenUSD dynamics paradigms (e.g., `UsdPhysicsDriveAPI` or solver force buffers). Controllers that directly manipulate spatial transforms must only actuate prims where `physics:kinematicEnabled = true`. Control schemas must not handle simulator-level state changes (e.g., native simulator state APIs or ROS `simulation_interfaces`), including resets for RL training or entity state manipulation. +* **Runtime selection:** A single asset may contain multiple, mutually exclusive control paradigms for the same hardware (e.g., trajectory control vs. direct effort control). While `VariantSets` remain the standard for structural hardware changes, control schemas must provide a dynamic enablement mechanism (e.g., `bool control:enabled`) to support runtime switching. The asset's default authored state must guarantee that overlapping controllers are not simultaneously active. + +#### 4.1.3 Sensor Schemas + +In addition to general extension schema rules, sensor schemas must follow these rules: +* **Ground Truth:** Sensor schemas must emulate measurable phenomena to ensure valid Software-in-the-Loop (SiL) testing. Simulator-generated Ground Truth artifacts (e.g., semantic segmentations, bounding boxes) must not be bundled into physical sensor schemas; they should be explicitly requested via dedicated annotator schemas. +* **Traversal:** Sensor schemas must be applied directly to the `UsdGeomXform` or `UsdGeomCamera` defining their physical origin and local coordinate frame. To ensure efficient parser discovery, these prims must reside in the asset's lightweight, traversable kinematic hierarchy. +* **Graceful Degradation:** Sensor schemas must define a functional, universal baseline of parameters. Advanced, engine-specific behaviors (e.g., proprietary rendering profiles, custom noise models) must be authored exclusively via vendor-namespaced custom attributes (e.g., `isaac:`, `gazebo:`). Simulators must safely ignore unrecognized namespaces and gracefully fall back to the universal baseline. + +### 4.2 Compliant Assets A canonincal repository of open-source, compliant simulation assets is to be established as `ros-simulation/openusd-assets`. These assets will have payloads hosted independently (e.g. in a dedicated repository such as Hugging Face) and must pass the Compliance Checker. + +## Tools + +### Core Schema Definition +The normative OpenUSD schema definition for all `Ros*API` schemas is provided in `schema/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. + +### Compliance Checker +A REP-XXXX compliance checker is to be developed and shared with the community. The tool will provide validation of all REP recommendations for OpenUSD assets and supply actionable feedback for the user for every violation or non-conformance. + + ## References * **[NVIDIA-ETL-PIPELINE]** NVIDIA, Intrinsic, Disney Research. "Using OpenUSD for Modular and Scalable Robotic Simulation and Development". URL: `https://developer.nvidia.com/blog/using-openusd-for-modular-and-scalable-robotic-simulation-and-development/` * **[NVIDIA-ASSETS]** NVIDIA, "Content Guidelines and Requirements". URL: `https://docs.omniverse.nvidia.com/kit/docs/asset-requirements/latest/index.html` From ba93017940e120e511972d169c3b60c9bd101bbb Mon Sep 17 00:00:00 2001 From: Adam Dabrowski Date: Tue, 14 Apr 2026 16:56:13 +0200 Subject: [PATCH 079/111] Applied some suggestions from review Signed-off-by: Adam Dabrowski --- rep.md | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/rep.md b/rep.md index da80d1f..8af124b 100644 --- a/rep.md +++ b/rep.md @@ -366,14 +366,14 @@ A canonical repository for these extensions is `ros-simulation/openusd-schemas`, Additional schemas are to be defined through extensions, chiefly for sensors and controls. They must follow these general rules: * **Use of Native Schemas:** Schema definitions must leverage core OpenUSD primitives to prevent attribute duplication. For example, `SensorCameraAPI` must apply to a `UsdGeomCamera` to append digital hardware metadata while natively reusing its optical properties. If no native analogue exists, schemas must be applied to a standard `UsdGeomXform`. -* **Separation of Transport:** Extension schemas must define purely physical or computational parameters (e.g., ray counts, wheel radius). They must not include metadata to handle ROS communication (e.g., topic names, QoS). Extension schemas should utilize relationships to target distinct transport prims (e.g., `RosTopicAPI`) to expose their data or commands. +* **Separation of Transport:** Extension schemas must not include metadata to handle ROS communication (e.g., topic names, QoS). Instead, they should utilize relationships to target distinct transport prims (e.g., `RosTopicAPI`) to expose their data or commands. #### 4.1.2 Control Schemas In addition to general extension schema rules, control interfaces and controllers must follow these rules: -* **Explicit Targeting:** Controllers must reside on dedicated logical prims (e.g., `/Robot/Controllers`) and explicitly target their actuated mechanisms. Simulators must not rely on Xform scene graph nesting to infer a controller's scope. Controllers must declare targets using OpenUSD relationships (`rel`) or standard `UsdCollectionAPI` collections. This guarantees modularity and robust path resolution when sub-assemblies are composed. -* **Actuation via Physics:** Control schemas must interface with dynamic bodies strictly through the simulation's physics pipeline. Position, velocity, and effort targets must be routed through normative OpenUSD dynamics paradigms (e.g., `UsdPhysicsDriveAPI` or solver force buffers). Controllers that directly manipulate spatial transforms must only actuate prims where `physics:kinematicEnabled = true`. Control schemas must not handle simulator-level state changes (e.g., native simulator state APIs or ROS `simulation_interfaces`), including resets for RL training or entity state manipulation. -* **Runtime selection:** A single asset may contain multiple, mutually exclusive control paradigms for the same hardware (e.g., trajectory control vs. direct effort control). While `VariantSets` remain the standard for structural hardware changes, control schemas must provide a dynamic enablement mechanism (e.g., `bool control:enabled`) to support runtime switching. The asset's default authored state must guarantee that overlapping controllers are not simultaneously active. +* **Explicit Targeting:** Controllers should be decoupled from the physical rigid-body hierarchy: authors should place them on dedicated logical prims (e.g., `/Robot/Controllers`) and explicitly target their actuated mechanisms. Simulators must not rely on Xform scene graph nesting to infer a controller's scope. Controllers must declare targets using OpenUSD relationships (`rel`) or standard `UsdCollectionAPI` collections. +* **Actuation via Physics:** Control schemas must interface with dynamic bodies strictly through the simulation's physics pipeline. Position, velocity, and effort targets must be routed through normative OpenUSD dynamics paradigms (e.g., `UsdPhysicsDriveAPI`) or universally ratified extension schemas, deferring to isolated vendor extensions only when a ratified standard for the required actuation modality does not exist. Controllers that directly manipulate spatial transforms must only actuate prims where `physics:kinematicEnabled = true`. Control schemas must not handle simulator-level state changes (e.g., native simulator state APIs or ROS `simulation_interfaces`), including resets for RL training or entity state manipulation. +* **Runtime selection:** A single asset may contain multiple, mutually exclusive control paradigms for the same hardware (e.g., trajectory control vs. direct effort control). While `VariantSets` remain the standard for structural hardware changes, control schemas must provide a dynamic enablement mechanism (e.g., `bool control:enabled`) to support runtime switching. The asset's default authored state must prevent write conflicts by ensuring controllers actuating same target are not simultaneously active. #### 4.1.3 Sensor Schemas From f1de0a041383992e6c27a5945d8bfaead6d68127 Mon Sep 17 00:00:00 2001 From: Adam Dabrowski Date: Wed, 15 Apr 2026 14:38:41 +0200 Subject: [PATCH 080/111] review changes Signed-off-by: Adam Dabrowski --- rep.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/rep.md b/rep.md index 8af124b..98f3ca2 100644 --- a/rep.md +++ b/rep.md @@ -372,8 +372,8 @@ Additional schemas are to be defined through extensions, chiefly for sensors and In addition to general extension schema rules, control interfaces and controllers must follow these rules: * **Explicit Targeting:** Controllers should be decoupled from the physical rigid-body hierarchy: authors should place them on dedicated logical prims (e.g., `/Robot/Controllers`) and explicitly target their actuated mechanisms. Simulators must not rely on Xform scene graph nesting to infer a controller's scope. Controllers must declare targets using OpenUSD relationships (`rel`) or standard `UsdCollectionAPI` collections. -* **Actuation via Physics:** Control schemas must interface with dynamic bodies strictly through the simulation's physics pipeline. Position, velocity, and effort targets must be routed through normative OpenUSD dynamics paradigms (e.g., `UsdPhysicsDriveAPI`) or universally ratified extension schemas, deferring to isolated vendor extensions only when a ratified standard for the required actuation modality does not exist. Controllers that directly manipulate spatial transforms must only actuate prims where `physics:kinematicEnabled = true`. Control schemas must not handle simulator-level state changes (e.g., native simulator state APIs or ROS `simulation_interfaces`), including resets for RL training or entity state manipulation. -* **Runtime selection:** A single asset may contain multiple, mutually exclusive control paradigms for the same hardware (e.g., trajectory control vs. direct effort control). While `VariantSets` remain the standard for structural hardware changes, control schemas must provide a dynamic enablement mechanism (e.g., `bool control:enabled`) to support runtime switching. The asset's default authored state must prevent write conflicts by ensuring controllers actuating same target are not simultaneously active. +* **Actuation via Physics:** Control schemas should interface with dynamic bodies strictly through the simulation's physics pipeline. Position, velocity, and effort targets must be routed through normative OpenUSD dynamics paradigms (e.g., `UsdPhysicsDriveAPI`) or universally ratified extension schemas, deferring to isolated vendor extensions only when a ratified standard for the required actuation modality does not exist. Controllers that directly manipulate spatial transforms should only actuate prims where `physics:kinematicEnabled = true`. Control schemas should not handle simulator-level state changes (e.g., native simulator state APIs or ROS `simulation_interfaces`), including resets for RL training or entity state manipulation. +* **Runtime selection:** A single asset may contain multiple, mutually exclusive control paradigms for the same hardware (e.g., trajectory control vs. direct effort control). While `VariantSets` remain the standard for structural hardware changes, simulators should provide dynamic lifecycle management of controllers to support runtime switching. The asset's authored state must prevent write conflicts at load time by ensuring controllers actuating the same targets are not simultaneously active (e.g., via a `bool control:starts_enabled` schema property). #### 4.1.3 Sensor Schemas From 835a0309ba5222e7406843e3e3e14a9db7ec46b7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Thu, 16 Apr 2026 09:52:37 +0200 Subject: [PATCH 081/111] Update rep.md Signed-off-by: Adam Dabrowski --- rep.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rep.md b/rep.md index 98f3ca2..d613d3b 100644 --- a/rep.md +++ b/rep.md @@ -301,7 +301,7 @@ If this property is missing, simulators must fall back to using the prim name. ## 3. Export and Conversion -OpenUSD is a vast standard supporting complex features. To guarantee that assets can be converted to glTF 2.0 and successfully exported to lightweight applications, assets must adhere to this constrained subset. +OpenUSD is a vast standard supporting complex features. To guarantee that assets can be converted to glTF 2.0 and successfully exported to work with lightweight applications and standard ROS tools (e.g., RViz, MoveIt) without mandating native OpenUSD support, assets must adhere to this constrained subset. ### 3.1 Material Portability * **Normative Surface:** Assets must use UsdPreviewSurface as the normative surface definition to ensure a direct mapping to glTF 2.0's pbrMetallicRoughness workflow. Target converters may also support OpenPBR[AOUSD-OPENPBR]. From 4921400ac4fd0fe8edaf6533b069416637afcc31 Mon Sep 17 00:00:00 2001 From: Adam Dabrowski Date: Thu, 16 Apr 2026 12:14:13 +0200 Subject: [PATCH 082/111] Changes suggested in PR #21 with substantial modifications: - override for frame_id - load-time enablement for interfaces - transform and scale rules - time scale (+ change in the units point) Co-authored-by: Franco Cipollone Signed-off-by: Adam Dabrowski --- rep.md | 14 +++++++++---- schema/schema.usda | 52 ++++++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 62 insertions(+), 4 deletions(-) diff --git a/rep.md b/rep.md index d613d3b..4137fb3 100644 --- a/rep.md +++ b/rep.md @@ -4,7 +4,7 @@ | :--- | :--- | | **REP** | XXXX | | **Title** | OpenUSD Conventions for Simulation Asset Interoperability | -| **Authors** | Adam Dabrowski, Mateusz Zak, Michal Pelka (Robotec.ai), Ayush Ghosh (NVIDIA) | +| **Authors** | Adam Dabrowski, Mateusz Zak, Michal Pelka (Robotec.ai), Ayush Ghosh (NVIDIA), Franco Cipollone (Ekumen) | | **Status** | Draft | | **Type** | Standards Track | | **Content-Type** | text/markdown | @@ -50,10 +50,11 @@ This section confirms and standardizes prior work and recommendations for OpenUS ### 1.1 Coordinate Systems & Units To ensure alignment with ROS standards (REP 103) and stability across solvers: -* **Units:** All linear dimensions in the USD stage must be defined in meters, and all mass values in kilograms. - * `metersPerUnit` and `kilogramsPerUnit` metadata must be set to `1.0` in the root layer. - * Fallback: while interoperable assets must adhere to 1.0, simulators and converters importing general OpenUSD assets must read these metadata tokens and apply the appropriate scaling factors to all derived spatial and physical quantities (e.g., coordinates, torque, stiffness, inertia) at load time +* **Standard Units (MKS):** Distributed assets must be natively authored in MKS (Meters, Kilograms, Seconds). Root layer metadata (`metersPerUnit`, `kilogramsPerUnit`, `timeCodesPerSecond`) must be explicitly set to 1.0. + * **No Runtime Scaling:** Upstream source units (e.g., CAD millimeters) must be physically baked into vertex data and physics properties (e.g., inertia tensors, joint limits) during the ETL pipeline. Relying on runtime metadata to globally rescale assets is prohibited, as it frequently corrupts non-linear physics across solvers. Simulators are entitled to assume `1.0` scaling. * **Up-Axis & Chirality:** The stage `upAxis` must be set to `"Z"`. Assets must follow the strict ROS Right-Handed coordinate convention: X-forward, Y-left, Z-up. +* **Transform Operations:** To guarantee a parity with ROS `geometry_msgs/Transform`, kinematic prims must use a minimal `xformOpOrder` stack: exactly one `xformOp:translate` and one `xformOp:orient` (quaternion). Baked 4x4 matrices (`xformOp:transform`) are prohibited on final assets, as they obscure scale and force costly runtime decomposition. While Euler angles (`xformOp:rotateXYZ`) are acceptable in source assets for human readability and URDF rpy alignment, ETL pipelines must convert all Euler rotations (translating URDF radians to USD degrees) and decompose all CAD matrices into this translate/orient format. +* **Scale Operations:** Kinematic prims (rigid bodies and joints) must maintain strict identity scale or omit `xformOp:scale` entirely. Non-identity scale on kinematic prims corrupts inertia tensors, distorts joint axes, and has no representation in the ROS TF tree. Any scaling such as non-uniform scaling to derive shapes must be pushed down and applied exclusively to the leaf visual or collision geometry prims. * **Root Transforms:** Assets must not rely on root-node rotations (e.g., `xformOp:rotateX = -90`) to align geometry. Points and normals should be transform-applied (frozen) to Z-up at the source level. * **Asset Pivots:** For assets intended to be placed on the ground (e.g., warehouse racks), the root origin should be located at the bottom-center of the asset bounding box (Z=0) to facilitate predictable drag-and-drop scene composition in simulators. Mobile bases should adhere to REP 105 origin conventions. @@ -235,6 +236,7 @@ ROS interface schemas (`RosTopicAPI`, `RosServiceAPI`, `RosActionAPI`) must be a For all schema types (Topics, Services, Actions) defined below: * **Type Resolution:** Tooling and compliant simulators must attempt to resolve the `ros:*:type` string (e.g., `sensor_msgs/msg/Image`) dynamically against the sourced ROS environment. If the interface type is not found, the simulator must safely disable that specific interface, allow the rest of the asset to function normally, and emit a distinct warning/error. * **Name Validation:** All `ros:*:name` values must strictly adhere to ROS topic naming rules (alphanumeric, underscores, and forward slashes only; cannot start with a number). +* **Initialization State:** All ROS interfaces (`RosTopicAPI`, `RosServiceAPI`, `RosActionAPI`) support a `bool ros:*:starts_enabled` attribute (`Optional`, `Default: true`). This dictates the initialization state of the interface at load time, preventing startup conflicts or unwanted compute overhead. Runtime lifecycle management (e.g., dynamically disabling the publisher mid-simulation) is the responsibility of the simulator. ### 2.4 Topic Interface (`RosTopicAPI`) Applies to Prims that exchange streaming ROS data. @@ -245,6 +247,10 @@ Applies to Prims that exchange streaming ROS data. * `string ros:topic:type`: The ROS message type. * `double ros:topic:publish_rate`: Target publication frequency in Hz. Required for publishers; ignored for subscriptions. +**Optional Override** + +* `string ros:topic:override_frame_id (Optional):` Overrides the `header.frame_id` populated in the published ROS message. This must only be used to reference external global frames (e.g., "map", "earth") that cannot exist natively within the USD stage. Relevant only for message types containing a `std_msgs/Header`. + **Quality of Service (QoS):** Maps directly to `rmw_qos_profile_t` policies. If an attribute is omitted, simulators must assume the specified defaults. *(Note: As per REP 2003, simulated sensors should default to `"system_default"` which maps to best-effort, while map publishers should use `"transient_local"`).* * `bool ros:topic:qos:match_publisher` (Optional, Default: `false`). For subscriptions only. If `true`, the simulator bridge must attempt to use ROS QoS matching to adapt to the discovered publisher, ignoring explicit reliability/durability settings. diff --git a/schema/schema.usda b/schema/schema.usda index 6ee03c6..2cdfe29 100644 --- a/schema/schema.usda +++ b/schema/schema.usda @@ -57,6 +57,13 @@ over "GLOBAL" ( dictionary world = { string doc = """Default parent frame for the top-most RosContextAPI.""" } + + # --- Enable/disable token --- + dictionary starts_enabled = { + string doc = """Common boolean attribute to indicate whether a ROS interface + is enabled at load time without removing the schema application. Runtime + lifecycle management is delegated to the simulator.""" + } } } ) @@ -171,6 +178,31 @@ class "RosTopicAPI" ( ignored for subscriptions.""" ) + # ------------------------------------------------------------------ + # Optional attributes + # ------------------------------------------------------------------ + + uniform string ros:topic:override_frame_id = "" ( + customData = { + string apiName = "overrideFrameId" + } + doc = """If non-empty, overrides the Header.frame_id populated in + the published message. When empty or omitted, simulators use the + TF frame name of the nearest ancestor that is a TF frame + (implicit or explicit). Only relevant for message types + containing a std_msgs/Header; ignored otherwise.""" + ) + + uniform bool ros:topic:starts_enabled = true ( + customData = { + string apiName = "startsEnabled" + } + doc = """If false, simulators must skip active instantiation of this + interface at load time. Allows VariantSets or composition overrides + to declaratively toggle interfaces. Runtime lifecycle management + remains the simulator's responsibility.""" + ) + # ------------------------------------------------------------------ # Quality of Service (QoS) Attributes # ------------------------------------------------------------------ @@ -260,6 +292,16 @@ class "RosServiceAPI" ( doc = """The ROS 2 service type (e.g. 'std_srvs/srv/SetBool'). Simulators must resolve dynamically; disable on failure.""" ) + + uniform bool ros2:starts_enabled = true ( + customData = { + string apiName = "startsEnabled" + } + doc = """If false, simulators must skip active instantiation of this + interface at load time. Allows VariantSets or composition overrides + to declaratively toggle interfaces. Runtime lifecycle management + remains the simulator's responsibility.""" + ) } # ====================================================================== @@ -304,6 +346,16 @@ class "RosActionAPI" ( (e.g. 'control_msgs/action/FollowJointTrajectory'). Simulators must resolve dynamically; disable on failure.""" ) + + uniform bool ros2:starts_enabled = true ( + customData = { + string apiName = "startsEnabled" + } + doc = """If false, simulators must skip active instantiation of this + interface at load time. Allows VariantSets or composition overrides + to declaratively toggle interfaces. Runtime lifecycle management + remains the simulator's responsibility.""" + ) } # ====================================================================== From e500cf26164c67d16c76691d0a654194dc93ea32 Mon Sep 17 00:00:00 2001 From: Adam Dabrowski Date: Thu, 16 Apr 2026 13:40:27 +0200 Subject: [PATCH 083/111] ros2 -> ros Co-authored-by: Franco Cipollone Signed-off-by: Adam Dabrowski --- schema/schema.usda | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/schema/schema.usda b/schema/schema.usda index 2cdfe29..bd734de 100644 --- a/schema/schema.usda +++ b/schema/schema.usda @@ -293,7 +293,7 @@ class "RosServiceAPI" ( Simulators must resolve dynamically; disable on failure.""" ) - uniform bool ros2:starts_enabled = true ( + uniform bool ros:starts_enabled = true ( customData = { string apiName = "startsEnabled" } @@ -347,7 +347,7 @@ class "RosActionAPI" ( Simulators must resolve dynamically; disable on failure.""" ) - uniform bool ros2:starts_enabled = true ( + uniform bool ros:starts_enabled = true ( customData = { string apiName = "startsEnabled" } From 83d0a72df3bbc8b4738ec856ea930598ee7c4257 Mon Sep 17 00:00:00 2001 From: Adam Dabrowski Date: Thu, 16 Apr 2026 14:02:40 +0200 Subject: [PATCH 084/111] Applied review - removed dictionary entry - removed empty def for frame override MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by Mateusz Żak Signed-off-by: Adam Dabrowski --- schema/schema.usda | 9 +-------- 1 file changed, 1 insertion(+), 8 deletions(-) diff --git a/schema/schema.usda b/schema/schema.usda index bd734de..4fda23e 100644 --- a/schema/schema.usda +++ b/schema/schema.usda @@ -57,13 +57,6 @@ over "GLOBAL" ( dictionary world = { string doc = """Default parent frame for the top-most RosContextAPI.""" } - - # --- Enable/disable token --- - dictionary starts_enabled = { - string doc = """Common boolean attribute to indicate whether a ROS interface - is enabled at load time without removing the schema application. Runtime - lifecycle management is delegated to the simulator.""" - } } } ) @@ -182,7 +175,7 @@ class "RosTopicAPI" ( # Optional attributes # ------------------------------------------------------------------ - uniform string ros:topic:override_frame_id = "" ( + uniform string ros:topic:override_frame_id ( customData = { string apiName = "overrideFrameId" } From b74afbfa5977a8f77da49713ac03c3bfe52722ae Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Thu, 16 Apr 2026 14:14:34 +0200 Subject: [PATCH 085/111] Update rep.md MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- rep.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rep.md b/rep.md index 4137fb3..d4b775d 100644 --- a/rep.md +++ b/rep.md @@ -50,7 +50,7 @@ This section confirms and standardizes prior work and recommendations for OpenUS ### 1.1 Coordinate Systems & Units To ensure alignment with ROS standards (REP 103) and stability across solvers: -* **Standard Units (MKS):** Distributed assets must be natively authored in MKS (Meters, Kilograms, Seconds). Root layer metadata (`metersPerUnit`, `kilogramsPerUnit`, `timeCodesPerSecond`) must be explicitly set to 1.0. +* **Standard Units (MKS):** Distributed assets must be natively authored in MKS (Meters, Kilograms, Seconds). Root layer metadata `metersPerUnit` and `kilogramsPerUnit` must be explicitly set to `1.0`. `timeCodesPerSecond` must also be set to `1.0` so that one USD time code equals one second, ensuring time-sampled data (e.g., animated joint trajectories) plays back at the correct rate without additional scaling. * **No Runtime Scaling:** Upstream source units (e.g., CAD millimeters) must be physically baked into vertex data and physics properties (e.g., inertia tensors, joint limits) during the ETL pipeline. Relying on runtime metadata to globally rescale assets is prohibited, as it frequently corrupts non-linear physics across solvers. Simulators are entitled to assume `1.0` scaling. * **Up-Axis & Chirality:** The stage `upAxis` must be set to `"Z"`. Assets must follow the strict ROS Right-Handed coordinate convention: X-forward, Y-left, Z-up. * **Transform Operations:** To guarantee a parity with ROS `geometry_msgs/Transform`, kinematic prims must use a minimal `xformOpOrder` stack: exactly one `xformOp:translate` and one `xformOp:orient` (quaternion). Baked 4x4 matrices (`xformOp:transform`) are prohibited on final assets, as they obscure scale and force costly runtime decomposition. While Euler angles (`xformOp:rotateXYZ`) are acceptable in source assets for human readability and URDF rpy alignment, ETL pipelines must convert all Euler rotations (translating URDF radians to USD degrees) and decompose all CAD matrices into this translate/orient format. From 2e32b9dc1f4a4884096cfd5e1b62020df4689bbc Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Thu, 16 Apr 2026 14:15:14 +0200 Subject: [PATCH 086/111] Apply suggestions from code review MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- schema/schema.usda | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/schema/schema.usda b/schema/schema.usda index 4fda23e..2ea1d5a 100644 --- a/schema/schema.usda +++ b/schema/schema.usda @@ -286,7 +286,7 @@ class "RosServiceAPI" ( Simulators must resolve dynamically; disable on failure.""" ) - uniform bool ros:starts_enabled = true ( + uniform bool ros:service:starts_enabled = true ( customData = { string apiName = "startsEnabled" } @@ -340,7 +340,7 @@ class "RosActionAPI" ( Simulators must resolve dynamically; disable on failure.""" ) - uniform bool ros:starts_enabled = true ( + uniform bool ros:action:starts_enabled = true ( customData = { string apiName = "startsEnabled" } From ddad28ffb65d34021a07d89d81cc09a358193ff3 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Mon, 20 Apr 2026 18:17:26 +0200 Subject: [PATCH 087/111] Refinements of points 1.1 and 1.2 Signed-off-by: Adam Dabrowski --- rep.md | 55 ++++++++++++++++++++++++++++--------------------------- 1 file changed, 28 insertions(+), 27 deletions(-) diff --git a/rep.md b/rep.md index d4b775d..1310201 100644 --- a/rep.md +++ b/rep.md @@ -33,7 +33,7 @@ The ROS ecosystem chiefly relies on URDF and SDF for describing robots and envir While OpenUSD adoption is growing quickly, only the core standard specification has been ratified so far, leaving most of what's interesting for robotics uncovered. OpenUSD lacks standardized semantic representations for ROS interfaces and standard rules for mapping to ROS concepts such as frames and TF trees. OpenUSD's flexibility also permits practices that degrade interoperability, such as proprietary extensions, defining execution instead of intent, and overfitting to particular workflows. -OpenUSD is championed by the Alliance for OpenUSD (AOUSD) and the ASWF USD Working Group. NVIDIA also plays a key role both as a founding member of AOUSD and in developing OpenUSD for robotics through Omniverse, Isaac Sim and Newton. This REP builds on top of great work done by all these entities, extending it by addressing what is not yet standardized but urgently needed for OpenUSD interoperability in the ROS simulation ecosystem, and standardizing against practices that result in a vendor lock-in. As such, this REP is designed to adapt upstream standards for the ROS community, while serving as a reference to influence future decisions by AOUSD and ASWF. +OpenUSD is championed by the Alliance for OpenUSD (AOUSD) and the ASWF USD Working Group. NVIDIA also plays a key role both as a founding member of AOUSD and in developing OpenUSD for robotics through Omniverse, Isaac Sim and Newton. This REP builds on top of significant work done by all these entities, extending it by addressing what is not yet standardized but urgently needed for OpenUSD interoperability in the ROS simulation ecosystem, and standardizing against practices that result in a vendor lock-in. As such, this REP is designed to adapt upstream standards for the ROS community, while serving as a reference to influence future decisions by AOUSD and ASWF. ## Specification @@ -50,74 +50,75 @@ This section confirms and standardizes prior work and recommendations for OpenUS ### 1.1 Coordinate Systems & Units To ensure alignment with ROS standards (REP 103) and stability across solvers: -* **Standard Units (MKS):** Distributed assets must be natively authored in MKS (Meters, Kilograms, Seconds). Root layer metadata `metersPerUnit` and `kilogramsPerUnit` must be explicitly set to `1.0`. `timeCodesPerSecond` must also be set to `1.0` so that one USD time code equals one second, ensuring time-sampled data (e.g., animated joint trajectories) plays back at the correct rate without additional scaling. - * **No Runtime Scaling:** Upstream source units (e.g., CAD millimeters) must be physically baked into vertex data and physics properties (e.g., inertia tensors, joint limits) during the ETL pipeline. Relying on runtime metadata to globally rescale assets is prohibited, as it frequently corrupts non-linear physics across solvers. Simulators are entitled to assume `1.0` scaling. -* **Up-Axis & Chirality:** The stage `upAxis` must be set to `"Z"`. Assets must follow the strict ROS Right-Handed coordinate convention: X-forward, Y-left, Z-up. +* **Standard Units (MKS):** Assets must use MKS (Meters, Kilograms, Seconds). Root layer metadata `metersPerUnit` and `kilogramsPerUnit` must be explicitly set to `1.0`. `timeCodesPerSecond` must also be set to `1.0` so that one USD time code equals one second, ensuring time-sampled data (e.g., animated joint trajectories) plays back at the correct rate without additional scaling. All upstream units (e.g., CAD millimeters) must be baked into geometry and physics during the Extract-Transform-Load (ETL) pipeline. Simulators are entitled to assume `1.0` scaling. +* **Up-Axis & Chirality:** The stage `upAxis` must be `"Z"`. Assets must follow the strict ROS Right-Handed convention: X-forward, Y-left, Z-up. * **Transform Operations:** To guarantee a parity with ROS `geometry_msgs/Transform`, kinematic prims must use a minimal `xformOpOrder` stack: exactly one `xformOp:translate` and one `xformOp:orient` (quaternion). Baked 4x4 matrices (`xformOp:transform`) are prohibited on final assets, as they obscure scale and force costly runtime decomposition. While Euler angles (`xformOp:rotateXYZ`) are acceptable in source assets for human readability and URDF rpy alignment, ETL pipelines must convert all Euler rotations (translating URDF radians to USD degrees) and decompose all CAD matrices into this translate/orient format. -* **Scale Operations:** Kinematic prims (rigid bodies and joints) must maintain strict identity scale or omit `xformOp:scale` entirely. Non-identity scale on kinematic prims corrupts inertia tensors, distorts joint axes, and has no representation in the ROS TF tree. Any scaling such as non-uniform scaling to derive shapes must be pushed down and applied exclusively to the leaf visual or collision geometry prims. +* **Scale Operations:** Kinematic prims (rigid bodies and joints) must maintain identity scale or omit `xformOp:scale` entirely. Scaling must be applied exclusively to the leaf visual or collision geometry prims. * **Root Transforms:** Assets must not rely on root-node rotations (e.g., `xformOp:rotateX = -90`) to align geometry. Points and normals should be transform-applied (frozen) to Z-up at the source level. -* **Asset Pivots:** For assets intended to be placed on the ground (e.g., warehouse racks), the root origin should be located at the bottom-center of the asset bounding box (Z=0) to facilitate predictable drag-and-drop scene composition in simulators. Mobile bases should adhere to REP 105 origin conventions. +* **Asset Pivots:** For assets intended to be placed on the ground (e.g., warehouse racks), the root origin should be located at the bottom-center of the bounding box (Z=0) to facilitate predictable drag-and-drop scene composition in simulators. Mobile bases should adhere to REP 105 origin conventions. ### 1.2 Asset Structure & Composition This REP adopts the ASWF Guidelines for Structuring USD Assets. #### 1.2.1 Schema Isolation and Functional Layering (The ETL Pipeline) -To avoid "Unknown Schema" errors in standard 3D authoring tools (e.g., Blender, Maya) and to ensure assets remain modular, functional layering (Extract-Transform-Load) should be utilized for ROS interfaces, physics, and simulator-specific tooling syntax. - -This REP endorses the ETL composition architecture developed collaboratively by NVIDIA, Intrinsic, and Disney Research for OpenUSD robotics assets. ![Extract-Transform-Load Pipeline for Robots in USD](etl_pipeline_diagram.png) *Figure 1: The Extract-Transform-Load (ETL) composition pipeline for OpenUSD robotics assets. Source: [NVIDIA Developer Blog](https://developer.nvidia.com/blog/using-openusd-for-modular-and-scalable-robotic-simulation-and-development/)* As illustrated in Figure 1, assets should be divided into functional layers composed via References and Payloads: -* **Asset Source & Transformation (The Base Layer):** The raw (e.g. CAD) data is optimized and decomposed into granular, functional files to maximize deduplication and performance. This layer contains core native OpenUSD schemas and should be structured as follows: - * `geometries.usd`: Contains pure mesh topology and vertices (no physics, no schemas). Most geometries should use the binary format (`.usdc`). - * `materials.usd`: Contains pure material definitions (`UsdShade`) and look-dev. - * `instances.usd` (Optional, recommended): Assembles geometries and materials via references. +* **Layer Separation:** Assets must use functional layering (ETL) to isolate core OpenUSD data from simulation and ROS-specific schemas. This prevents "Unknown Schema" errors in standard tools and enables modular updates. +* **The Base Layer:** The core data must be decomposed into granular, functional files to maximize deduplication and performance: + * `geometries.usd`: Contains pure mesh topology and vertices (no physics, no schemas), typically as `.usdc`. + * `materials.usd`: Contains material and look-dev definitions. + * `instances.usd`: (Optional, recommended): Assembles geometries and materials via references. * `base.usd`: The pure kinematic hierarchy (Xforms), referencing the underlying instances and geometries without physical or execution logic. -* **Features (The Domain-Specific Layers):** Domain metadata is isolated into specific overlay files that reference the Base Layer. For example, `asset_physics.usd` contains the rigid bodies and joints, while `asset_ros.usd` contains the `Ros*API` schemas defined in this REP. -* **Entry Point (`asset.usd`):** The final distributed asset is a lightweight interface layer that uses **Payloads** to load the Features. -* **Proprietary Layer:** Asset authors should avoid including heavy, simulator-specific implementations (e.g., proprietary execution graphs) within the interoperable asset package. If unavoidable, they must minimize this proprietary layer (e.g., `isaac.usd`, `o3de.usd`) to what is strictly necessary and keep it isolated as a separate Feature layer. +* **Features (The Domain-Specific Layers):** Domain metadata must be isolated into overlay files, including: + * `physics.usd`: Contains `UsdPhysics` rigid bodies and joints. + * `ros.usd`: Contains the `Ros*API` schemas. +* **Entry Point (`[asset_name].usd`):** The final distributed asset must be a lightweight interface layer that uses **Payloads** to load the Features. +* **Proprietary Layer:** Simulator-specific implementations (e.g., proprietary execution graphs) must be limited to what is strictly necessary and confined to a separate proprietary layer (e.g., `isaac.usd`, `o3de.usd`). #### 1.2.2 The Composition Model -* **Components:** Atomic assets (e.g., a `LidarSensor`, a `Box`) must have `kind="component"` on their root prim. +Assets must adhere to the OpenUSD Model Hierarchy to ensure predictable selection and traversal: +* **Components:** Idividual distributable assets assets (e.g., a sensor, a box) must have `kind="component"` on their root prim. * **Assemblies:** Aggregates (e.g., a `Warehouse` containing racks) must have `kind="assembly"` or `kind="group"`. -* A `component` must not contain another `component`: if finer organizational granularity is required, authors must use kind="subcomponent" allowing converters to easily identify the "atomic units" of the scene. +* **Granularity:** Authors should use kind="subcomponent" for organizational prims within a component. #### 1.2.3 Composition Arcs (LIVRPS Constraints) To guarantee that simulation assets remain self-contained, portable, and predictable across different simulator parsers, asset authors must adhere to the following constraints regarding OpenUSD's LIVRPS composition arcs: * **[L] Local:** Primary authoring of overrides and properties on the asset is fully supported. -* **[I] Inherits & [S] Specializes:** Asset authors should not rely on `Inherits` or `Specializes` arcs that target class definitions outside the asset's own layer stack for core robot kinematics, physics APIs, or ROS schemas when distributing standalone assets. These arcs create hard dependencies on external class hierarchies; if a simulator's environment lacks the base class definitions, the asset will fail to parse correctly. The inherits-instanceable pattern, where the class prim is defined within the same asset, remains valid and is recommended for applying uniform overrides across instances. +* **[I] Inherits & [S] Specializes:** Asset authors should not rely on `Inherits` or `Specializes` arcs that target class definitions outside the asset's own layer stack for core robot kinematics, physics APIs, or ROS schemas when distributing standalone assets. The inherits-instanceable pattern, where the class prim is defined within the same asset, remains valid and is recommended for applying uniform overrides across instances. * **[V] VariantSets:** Permitted and encouraged for asset reusability (see Section 1.2.4). * **[R] References:** Permitted for logical assembly (e.g., composing a robot by referencing an independent `arm.usd` and `base.usd`). * **[P] Payloads (The Payload Pattern):** Heavy data (high-resolution meshes, point clouds, large textures) must be referenced via Payloads rather than standard References. - * Payloads must not gate joint or link prims themselves. The kinematic topology (Prims bearing `PhysicsRigidBodyAPI`, `PhysicsJoint` schemas, and `Ros*API` schemas) must reside in the primarily loaded scene graph (e.g., via Local authoring or standard References). + * Payloads must not encapsulate joint or link prims themselves. The kinematic topology (Prims bearing `PhysicsRigidBodyAPI`, `PhysicsJoint` schemas, and `Ros*API` schemas) must reside in the primarily loaded scene graph (e.g., via Local authoring or standard References). * The Payload should solely encapsulate the nested geometric and material data. This enables ROS parsers and web converters to traverse the lightweight kinematic tree efficiently without loading heavy buffers. #### 1.2.4 Variants OpenUSD `VariantSets` are the normative mechanism for asset reusability (e.g., encapsulating multiple furniture styles, different robot end-effectors, or optional sensor suites within a single asset). -* **Default Variant Fallback:** Any asset utilizing `VariantSets` must author a default variant selection. This ensures that if the asset is loaded by a simulator or CI/CD pipeline without explicit variant overrides, it resolves to a valid, predictable physical and visual state. -* **ROS Interface Resolution:** A change in a variant selection may add or remove Prims containing `Ros*API` schemas (e.g., swapping a generic robot head for a sensor-equipped head). Simulators and tooling must only evaluate and spawn ROS interfaces that are active within the currently resolved variant state of the stage. +* **Default Variant Fallback:** Any asset utilizing `VariantSets` must author a default variant selection. This ensures that if the asset is loaded by a simulator or automated pipeline without explicit variant overrides, it resolves to a valid, physically and visually complete state. +* **ROS Interface Resolution:** A change in a variant selection may add or remove Prims containing `Ros*API` schemas (e.g., swapping a generic robot head for a sensor-equipped head). Simulators and tooling must only evaluate and instantiate ROS interfaces that are active within the currently resolved variant state of the stage. #### 1.2.5 Asset Management * **Default Prim:** All distributable assets must set `defaultPrim` metadata on the root layer, pointing to the asset's primary entrypoint prim. Without it, referencing `@robot.usd@` without an explicit prim path is undefined behavior and the Payload pattern breaks silently. * **Asset Identification (`assetInfo`):** All distributable assets must populate the `assetInfo` dictionary on the `defaultPrim` with at minimum: * `string assetInfo:identifier`: A unique, stable identifier for the asset (e.g., a URI or canonical name). * `string assetInfo:version`: A version string (e.g., `"1.0.0"`). - * For robotics-specific identifiers that must be carried today (e.g., URDF package origin, original SDF model URI), authors should use a namespaced sub-dictionary (e.g., `assetInfo["ros"]`) following the `UsdMediaAssetPreviewsAPI` precedent. This is a vendor-tier convention positioned for promotion once a broader standard settles. - * *Note: An active AOUSD proposal: [Separation of Concerns for Identifiers in USD (PR #105)](https://github.com/PixarAnimationStudios/OpenUSD-proposals/pull/105) is evaluating standardized mechanisms for carrying external source identifiers (e.g., PLM part numbers, OPC UA NodeIds, equipment tags) in USD. This REP will adopt the ratified upstream standard once finalized, replacing the interim `assetInfo` convention above.* + * To carry robotics-specific provenance (e.g., URDF package origin, original SDFormat model URI, or component catalog IDs), authors should use a namespaced sub-dictionary: assetInfo["ros"]. + *Example: `assetInfo["ros"]["package_uri"] = "package://my_robot/urdf/robot.urdf"`. + * *Note: This REP aligns with the domain convention requested in the active AOUSD proposal: [Separation of Concerns for Identifiers in USD (PR #105)](https://github.com/PixarAnimationStudios/OpenUSD-proposals/pull/105) Once AOUSD ratifies a standardized mechanism for external identifiers, this REP will adopt it.* * **Path Resolution:** Internal references must use relative paths (`./geo/mesh.usdc`). For distributed, highly interoperable assets, all file dependencies should be self-contained and rely exclusively on relative paths. -* **ROS packages:** External dependencies to other ROS packages must use the package:// URI scheme, and should be contained in ROS-specific .usd files in the ETL pipeline. Asset authors must be aware that resolving these URIs requires the host simulator or tool to implement a custom OpenUSD ArResolver plugin. Absolute paths and proprietary schemes (e.g., omniverse://) are strictly prohibited in distributed assets. +* **ROS packages:** External dependencies targeting other ROS packages must use the package:// URI scheme. Absolute paths or proprietary schemes (e.g., omniverse://) are prohibited for external package references. Tooling and simulators aiming for ROS interoperability must provide a custom OpenUSD ArResolver plugin to resolve these URIs. * **Native Composition vs. Custom Prefabs:** The use of custom or vendor-specific string attributes (e.g., `custom string my_sim:prefabPath = "robot.usd"`) to dynamically load, instantiate, or compose assets at runtime is strictly prohibited for interoperable assets. Asset composition must rely purely on native OpenUSD references or payloads. -* **FileFormat Plugins:** OpenUSD supports FileFormat plugins (e.g., MuJoCo's `usdMjcf` plugin) to dynamically translate legacy formats into USD stages at runtime. While these plugins are recommended for import pathways, this REP governs the *resulting in-memory OpenUSD data*. Plugins interfacing with the ROS ecosystem must generate stages that conform to the physical hierarchies and API schemas defined in this document. +* **FileFormat Plugins:** OpenUSD supports FileFormat plugins (e.g.,`usdMjcf`) to dynamically translate legacy formats into USD stages at runtime. While these plugins are recommended for import pathways, this REP governs the *resulting in-memory OpenUSD data*. Plugins interfacing with the ROS ecosystem must generate stages that conform to the physical hierarchies and API schemas defined in this document. #### 1.2.6 Parallel Simulation and Instancing OpenUSD's native instancing mechanisms are designed for repetitive visual and structural geometry. They must not be used to clone articulated physics assets to create massive parallel arrays (e.g., for reinforcement learning). * **Canonical Assets:** Authors must distribute a single, self-contained canonical environment. -* **Runtime Delegation:** Simulators supporting massive parallelism are expected to handle environment replication natively at runtime via their own APIs. Authors must not bake thousands of physics-enabled clones into the source file. +* **Runtime Delegation:** Simulators supporting massive parallelism are expected to handle environment replication natively at runtime via their own APIs. Authors must not bake arrays of physics-enabled clones into the source file. ### 1.3 Physics * **Joint Placement:** Asset authors should place the joint prim as a sibling adjacent to the child link it connects, within the scope of the parent link, to ensure self-contained modularity. Note that `UsdPhysicsJoint` prims rely on relational targeting (`body0` and `body1`) rather than hierarchy, which means parsers must reconstruct the kinematic tree exclusively from these relationships. From f3a3b20538872935c4986ad92e19848deb881d96 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Tue, 21 Apr 2026 13:18:10 +0200 Subject: [PATCH 088/111] chore: fix typos Signed-off-by: Adam Dabrowski --- rep.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/rep.md b/rep.md index 1310201..836c091 100644 --- a/rep.md +++ b/rep.md @@ -83,7 +83,7 @@ As illustrated in Figure 1, assets should be divided into functional layers comp #### 1.2.2 The Composition Model Assets must adhere to the OpenUSD Model Hierarchy to ensure predictable selection and traversal: -* **Components:** Idividual distributable assets assets (e.g., a sensor, a box) must have `kind="component"` on their root prim. +* **Components:** Individual distributable assets (e.g., a sensor, a box) must have `kind="component"` on their root prim. * **Assemblies:** Aggregates (e.g., a `Warehouse` containing racks) must have `kind="assembly"` or `kind="group"`. * **Granularity:** Authors should use kind="subcomponent" for organizational prims within a component. @@ -108,7 +108,7 @@ OpenUSD `VariantSets` are the normative mechanism for asset reusability (e.g., e * `string assetInfo:identifier`: A unique, stable identifier for the asset (e.g., a URI or canonical name). * `string assetInfo:version`: A version string (e.g., `"1.0.0"`). * To carry robotics-specific provenance (e.g., URDF package origin, original SDFormat model URI, or component catalog IDs), authors should use a namespaced sub-dictionary: assetInfo["ros"]. - *Example: `assetInfo["ros"]["package_uri"] = "package://my_robot/urdf/robot.urdf"`. + *Example: `assetInfo["ros"]["package_uri"] = "package://my_robot/urdf/robot.urdf"`.* * *Note: This REP aligns with the domain convention requested in the active AOUSD proposal: [Separation of Concerns for Identifiers in USD (PR #105)](https://github.com/PixarAnimationStudios/OpenUSD-proposals/pull/105) Once AOUSD ratifies a standardized mechanism for external identifiers, this REP will adopt it.* * **Path Resolution:** Internal references must use relative paths (`./geo/mesh.usdc`). For distributed, highly interoperable assets, all file dependencies should be self-contained and rely exclusively on relative paths. * **ROS packages:** External dependencies targeting other ROS packages must use the package:// URI scheme. Absolute paths or proprietary schemes (e.g., omniverse://) are prohibited for external package references. Tooling and simulators aiming for ROS interoperability must provide a custom OpenUSD ArResolver plugin to resolve these URIs. From 8ca31d6414f5cda610849057479ebc76f2fddc46 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Mon, 27 Apr 2026 12:41:51 +0200 Subject: [PATCH 089/111] make layer encoding explicit MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - Add a Layer Encoding rule: ascii for light, crate for heavy - Update the extenctions to canonical Co-authored-by: Renato Gasoto Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- rep.md | 29 +++++++++++++++-------------- 1 file changed, 15 insertions(+), 14 deletions(-) diff --git a/rep.md b/rep.md index 836c091..ccf0549 100644 --- a/rep.md +++ b/rep.md @@ -69,16 +69,17 @@ This REP adopts the ASWF Guidelines for Structuring USD Assets. As illustrated in Figure 1, assets should be divided into functional layers composed via References and Payloads: * **Layer Separation:** Assets must use functional layering (ETL) to isolate core OpenUSD data from simulation and ROS-specific schemas. This prevents "Unknown Schema" errors in standard tools and enables modular updates. +* **Layer Encoding:** Schema- and relationship-bearing layers must be authored as ASCII (`.usda`); heavy-data layers as binary Crate (`.usdc`). * **The Base Layer:** The core data must be decomposed into granular, functional files to maximize deduplication and performance: - * `geometries.usd`: Contains pure mesh topology and vertices (no physics, no schemas), typically as `.usdc`. - * `materials.usd`: Contains material and look-dev definitions. - * `instances.usd`: (Optional, recommended): Assembles geometries and materials via references. - * `base.usd`: The pure kinematic hierarchy (Xforms), referencing the underlying instances and geometries without physical or execution logic. + * `geometries.usdc`: Contains pure mesh topology and vertices (no physics, no schemas). + * `materials.usda`: Contains material and look-dev definitions. + * `instances.usda`: (Optional, recommended): Assembles geometries and materials via references. + * `base.usda`: The pure kinematic hierarchy (Xforms), referencing the underlying instances and geometries without physical or execution logic. * **Features (The Domain-Specific Layers):** Domain metadata must be isolated into overlay files, including: - * `physics.usd`: Contains `UsdPhysics` rigid bodies and joints. - * `ros.usd`: Contains the `Ros*API` schemas. -* **Entry Point (`[asset_name].usd`):** The final distributed asset must be a lightweight interface layer that uses **Payloads** to load the Features. -* **Proprietary Layer:** Simulator-specific implementations (e.g., proprietary execution graphs) must be limited to what is strictly necessary and confined to a separate proprietary layer (e.g., `isaac.usd`, `o3de.usd`). + * `physics.usda`: Contains `UsdPhysics` rigid bodies and joints. + * `ros.usda`: Contains the `Ros*API` schemas. +* **Entry Point (`[asset_name].usda`):** The final distributed asset must be a lightweight interface layer that uses **Payloads** to load the Features. +* **Proprietary Layer:** Simulator-specific implementations (e.g., proprietary execution graphs) must be limited to what is strictly necessary and confined to a separate proprietary layer (e.g., `isaac.usda`, `o3de.usda`). #### 1.2.2 The Composition Model @@ -92,7 +93,7 @@ To guarantee that simulation assets remain self-contained, portable, and predict * **[L] Local:** Primary authoring of overrides and properties on the asset is fully supported. * **[I] Inherits & [S] Specializes:** Asset authors should not rely on `Inherits` or `Specializes` arcs that target class definitions outside the asset's own layer stack for core robot kinematics, physics APIs, or ROS schemas when distributing standalone assets. The inherits-instanceable pattern, where the class prim is defined within the same asset, remains valid and is recommended for applying uniform overrides across instances. * **[V] VariantSets:** Permitted and encouraged for asset reusability (see Section 1.2.4). -* **[R] References:** Permitted for logical assembly (e.g., composing a robot by referencing an independent `arm.usd` and `base.usd`). +* **[R] References:** Permitted for logical assembly (e.g., composing a robot by referencing an independent `arm.usda` and `base.usda`). * **[P] Payloads (The Payload Pattern):** Heavy data (high-resolution meshes, point clouds, large textures) must be referenced via Payloads rather than standard References. * Payloads must not encapsulate joint or link prims themselves. The kinematic topology (Prims bearing `PhysicsRigidBodyAPI`, `PhysicsJoint` schemas, and `Ros*API` schemas) must reside in the primarily loaded scene graph (e.g., via Local authoring or standard References). * The Payload should solely encapsulate the nested geometric and material data. This enables ROS parsers and web converters to traverse the lightweight kinematic tree efficiently without loading heavy buffers. @@ -103,7 +104,7 @@ OpenUSD `VariantSets` are the normative mechanism for asset reusability (e.g., e * **ROS Interface Resolution:** A change in a variant selection may add or remove Prims containing `Ros*API` schemas (e.g., swapping a generic robot head for a sensor-equipped head). Simulators and tooling must only evaluate and instantiate ROS interfaces that are active within the currently resolved variant state of the stage. #### 1.2.5 Asset Management -* **Default Prim:** All distributable assets must set `defaultPrim` metadata on the root layer, pointing to the asset's primary entrypoint prim. Without it, referencing `@robot.usd@` without an explicit prim path is undefined behavior and the Payload pattern breaks silently. +* **Default Prim:** All distributable assets must set `defaultPrim` metadata on the root layer, pointing to the asset's primary entrypoint prim. Without it, referencing `@robot.usda@` without an explicit prim path is undefined behavior and the Payload pattern breaks silently. * **Asset Identification (`assetInfo`):** All distributable assets must populate the `assetInfo` dictionary on the `defaultPrim` with at minimum: * `string assetInfo:identifier`: A unique, stable identifier for the asset (e.g., a URI or canonical name). * `string assetInfo:version`: A version string (e.g., `"1.0.0"`). @@ -166,8 +167,8 @@ To ensure deterministic contact dynamics across engines, authors must bind a `Us To guarantee interoperability across different solvers, physical properties and engine-specific parameters must be explicitly decoupled into separate functional layers: -* **Neutral Physics (`physics.usd`):** A universally shared layer containing exclusively core `UsdPhysics` schemas (rigid bodies, joints, limits, mass properties). This file must strictly adhere to the standard OpenUSD Physics specification and must not contain any vendor-specific extensions. -* **Engine Tuning (`physx.usd`, `mujoco.usd`, `isaac.usd`):** Engine-specific parameters (e.g., proprietary solver iterations, specialized friction models, GPU tensors) not covered by core OpenUSD schemas must be explicitly namespaced with a vendor prefix (e.g., `mujoco:`, `isaac:`). These must be strictly isolated within discrete "Proprietary Layers" (Section 1.2.1) and never authored in the baseline simulation payload or neutral physics layer. Authors must strive to minimize this proprietary layer to what is strictly necessary. +* **Neutral Physics (`physics.usda`):** A universally shared layer containing exclusively core `UsdPhysics` schemas (rigid bodies, joints, limits, mass properties). This file must strictly adhere to the standard OpenUSD Physics specification and must not contain any vendor-specific extensions. +* **Engine Tuning (`physx.usda`, `mujoco.usda`, `isaac.usda`):** Engine-specific parameters (e.g., proprietary solver iterations, specialized friction models, GPU tensors) not covered by core OpenUSD schemas must be explicitly namespaced with a vendor prefix (e.g., `mujoco:`, `isaac:`). These must be strictly isolated within discrete "Proprietary Layers" (Section 1.2.1) and never authored in the baseline simulation payload or neutral physics layer. Authors must strive to minimize this proprietary layer to what is strictly necessary. --- @@ -205,14 +206,14 @@ def Xform "robot" ( string ros:context:namespace = "robot_1" def Xform "camera_left" ( - references = @./camera_module.usd@ + references = @./camera_module.usda@ prepend apiSchemas = ["RosContextAPI"] ) { string ros:context:namespace = "camera_left" # overrides "camera" from source } def Xform "camera_right" ( - references = @./camera_module.usd@ + references = @./camera_module.usda@ prepend apiSchemas = ["RosContextAPI"] ) { string ros:context:namespace = "camera_right" # overrides "camera" from source From 8f3b20fa18b0affdf7ba3037f2fc37865c662e72 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Mon, 27 Apr 2026 15:38:19 +0200 Subject: [PATCH 090/111] forbid shadow definitions in proprietary layers MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit State directly that: - assets must not duplicate the same ROS interface in another form - persisted runtime artifacts go in the proprietary layer Co-authored-by: Renato Gasoto Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- rep.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rep.md b/rep.md index ccf0549..0e5aa58 100644 --- a/rep.md +++ b/rep.md @@ -174,7 +174,7 @@ To guarantee interoperability across different solvers, physical properties and ## 2. ROS Integration Schemas -Neither OpenUSD nor glTF 2.0 currently standardize the specification of ROS interfaces. This section defines a set of declarative, engine-agnostic API schemas (of type `SingleApply`). Simulators are responsible for reading these schemas and generating their respective underlying execution logic. +Neither OpenUSD nor glTF 2.0 currently standardize the specification of ROS interfaces. This section defines a set of declarative, engine-agnostic API schemas (of type `SingleApply`). Simulators are responsible for reading these schemas and generating their respective underlying execution logic. Assets must not duplicate the same ROS interface in another form (e.g., a hand-authored execution graph publishing the same topic alongside the authored `Ros*API` schema); persisted runtime artifacts belong in the simulator's proprietary layer (Section 1.2.1), not in the neutral ROS layer. ### 2.1 The ROS Context (`RosContextAPI`) The root prim of a ROS-interfaced simulation asset may define its context namespace. From bcc5115bcfc46f613fda21ca962d472074c2636a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Tue, 28 Apr 2026 12:07:36 +0200 Subject: [PATCH 091/111] add rgasoto as Author MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- rep.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rep.md b/rep.md index 0e5aa58..6c1517c 100644 --- a/rep.md +++ b/rep.md @@ -4,7 +4,7 @@ | :--- | :--- | | **REP** | XXXX | | **Title** | OpenUSD Conventions for Simulation Asset Interoperability | -| **Authors** | Adam Dabrowski, Mateusz Zak, Michal Pelka (Robotec.ai), Ayush Ghosh (NVIDIA), Franco Cipollone (Ekumen) | +| **Authors** | Adam Dabrowski, Mateusz Zak, Michal Pelka (Robotec.ai), Ayush Ghosh, Renato Gasoto (NVIDIA), Franco Cipollone (Ekumen) | | **Status** | Draft | | **Type** | Standards Track | | **Content-Type** | text/markdown | From 23bdf7f41811c02fbb2916339612f991a8faefe6 Mon Sep 17 00:00:00 2001 From: Adam Dabrowski Date: Mon, 27 Apr 2026 13:54:15 +0200 Subject: [PATCH 092/111] WIP: extended physics, reorganization of files, minor tweaks Signed-off-by: Adam Dabrowski --- {schema => core/ros}/schema.usda | 0 .../control}/control_extension.md | 0 .../control}/schema/schema.usda | 0 extensions/physics/README.md | 13 +++++ extensions/physics/schema.usda | 0 rep.md | 54 ++++++++++++------- 6 files changed, 49 insertions(+), 18 deletions(-) rename {schema => core/ros}/schema.usda (100%) rename {control => extensions/control}/control_extension.md (100%) rename {control => extensions/control}/schema/schema.usda (100%) create mode 100644 extensions/physics/README.md create mode 100644 extensions/physics/schema.usda diff --git a/schema/schema.usda b/core/ros/schema.usda similarity index 100% rename from schema/schema.usda rename to core/ros/schema.usda diff --git a/control/control_extension.md b/extensions/control/control_extension.md similarity index 100% rename from control/control_extension.md rename to extensions/control/control_extension.md diff --git a/control/schema/schema.usda b/extensions/control/schema/schema.usda similarity index 100% rename from control/schema/schema.usda rename to extensions/control/schema/schema.usda diff --git a/extensions/physics/README.md b/extensions/physics/README.md new file mode 100644 index 0000000..b0f0aad --- /dev/null +++ b/extensions/physics/README.md @@ -0,0 +1,13 @@ +# Extended Physics Schema + +This schema provides an extended feature set for OpenUSD physics. It draws inspiration from work on [Newton Schemas](https://github.com/newton-physics/newton-usd-schemas), but ensures neutral naming and focus on full interoperabilty. + + +## Mimic Joints + +Joints whose position is a linear function of another joint (e.g., parallel gripper fingers, coupled mechanisms) must declare the coupling declaratively using `ExtendedPhysicsMimicJointAPI`, a **SingleApply** API schema applied to the follower joint. `ExtendedPhysicsMimicJointAPI` must only be applied to `UsdPhysicsRevoluteJoint` or `UsdPhysicsPrismaticJoint` prims. The coupling operates on the joint's native positional value. +* `rel mimic:joint`: Relationship to the source joint. Must use a USD relationship (not a string attribute) to ensure correct path remapping under composition arcs. Mimic relationships must form a Directed Acyclic Graph (DAG); chained couplings are valid, but cycles are prohibited. +* `float mimic:multiplier` (Default: `1.0`): Scale factor. `follower_position = multiplier * source_position + offset`. +* `float mimic:offset` (Default: `0.0`): Constant offset in the source joint's native units. +* *Note: UsdPhysics does not currently provide a joint coupling mechanism. This schema fills that gap. Should AOUSD/ASWF standardize an equivalent under `UsdPhysics`, this REP would adopt the upstream schema.* + diff --git a/extensions/physics/schema.usda b/extensions/physics/schema.usda new file mode 100644 index 0000000..e69de29 diff --git a/rep.md b/rep.md index 6c1517c..e1d941b 100644 --- a/rep.md +++ b/rep.md @@ -134,12 +134,8 @@ OpenUSD's native instancing mechanisms are designed for repetitive visual and st * *Kinematic Bodies:* Moving bodies that are animated but not dynamically driven by physics should set the physics:kinematicEnabled attribute to true. * *Dummy Frames:* Non-physical dummy frames (e.g., `camera_optical_frame`) must not possess a `PhysicsRigidBodyAPI`. They should be tracked using the `RosFrameAPI` as defined in Section 2.8. * **Inertia Representation:** Unlike URDF and SDFormat's 6-value symmetric matrix, OpenUSD requires an eigendecomposed inertia tensor. Converters must mathematically decompose the source matrix into physics:diagonalInertia (eigenvalues) and physics:principalAxes (quaternion). This native decomposed form is the strict single source of truth; custom 6-value array attributes must not be authored or parsed. -* **Mimic Joints:** Joints whose position is a linear function of another joint (e.g., parallel gripper fingers, coupled mechanisms) must declare the coupling declaratively using `MimicJointAPI`, a **SingleApply** API schema applied to the follower joint. `MimicJointAPI` must only be applied to `UsdPhysicsRevoluteJoint` or `UsdPhysicsPrismaticJoint` prims. The coupling operates on the joint's native positional value. - * `rel mimic:joint`: Relationship to the source joint. Must use a USD relationship (not a string attribute) to ensure correct path remapping under composition arcs. Mimic relationships must form a Directed Acyclic Graph (DAG); chained couplings are valid, but cycles are prohibited. - * `float mimic:multiplier` (Default: `1.0`): Scale factor. `follower_position = multiplier * source_position + offset`. - * `float mimic:offset` (Default: `0.0`): Constant offset in the source joint's native units. - * *Note: UsdPhysics does not currently provide a joint coupling mechanism. This schema fills that gap. Should AOUSD/ASWF standardize an equivalent under `UsdPhysics`, this REP would adopt the upstream schema.* -* **Deformable Bodies:** A vendor-neutral schema for deformable bodies is not yet ratified. Assets must isolate deformable soft-body physics into feature layer for specific domain or vendor (see Section 1.2.1). The asset's default variant must provide a rigid-body fallback approximation for interoperability. +* **Extended Physics:** Many physics features are missing in `USDPhysics`, including mimic joints, deformable bodies and advanced friction. Authors must use `ExtendedPhysics*` schemas for interoperability, following Section 4.2.2. When interoperable schema is not available, assets must isolate specific feature, e.g. deformable soft-body physics into a feature layer for specific domain or vendor (see Section 1.2.1). + #### 1.3.1 Collisions Collision geometries should explicitly specify `purpose="guide"` and `physics:approximation="none"`. To ensure assets function across both standard physics engines and advanced contact-rich solvers (e.g., Newton), assets should employ a "Dual-Fidelity Pattern" utilizing a `collision_fidelity` OpenUSD `VariantSet`: @@ -309,7 +305,7 @@ If this property is missing, simulators must fall back to using the prim name. ## 3. Export and Conversion -OpenUSD is a vast standard supporting complex features. To guarantee that assets can be converted to glTF 2.0 and successfully exported to work with lightweight applications and standard ROS tools (e.g., RViz, MoveIt) without mandating native OpenUSD support, assets must adhere to this constrained subset. +OpenUSD is a vast standard supporting complex features. To guarantee that assets can be converted to glTF 2.0 and successfully exported to work with lightweight applications and standard ROS tools (e.g., RViz, MoveIt), such as for publishing of a URDF string to `/robot_description`, without mandating native OpenUSD support, assets must adhere to this constrained subset. ### 3.1 Material Portability * **Normative Surface:** Assets must use UsdPreviewSurface as the normative surface definition to ensure a direct mapping to glTF 2.0's pbrMetallicRoughness workflow. Target converters may also support OpenPBR[AOUSD-OPENPBR]. @@ -361,48 +357,69 @@ OpenUSD and robotics XML formats (URDF, SDF, MJCF) are fundamentally mismatched ## 4. The Interoperability Ecosystem -Due to the number and dynamic nature of control and sensor types, these will be handled as extension schemas to interoperability profile compliance. They will be submitted and ratified independently. +A canonical repository for core schema, extension schemas and compliance tooling is `ros-simulation/openusd-schemas`. + +### 4.1 Core ROS Schema Definition +The normative OpenUSD schema definition for all `Ros*API` schemas is provided in `schema/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. + -### 4.1 Schema Registry +### 4.2 Schema Registry + +Due to the number and dynamic nature of extensions for physics, controls and sensors, they will be handled as extension schemas to interoperability profile compliance. Extension schemas will be submitted and ratified independently. The following is mandated: -A canonical repository for these extensions is `ros-simulation/openusd-schemas`, and the following is mandated: - A submission must follow the rules of this REP where applicable, e.g. including declarative parameters that can be implemented accross simulators, and adhering to general rules for sensors and control schemas (e.g. graceful degradation). A submission may include one or more vendor or physic engine specific layers as outlined in Section 1.4. -- A submission must include addition to Compliance Checker which allows the use of new schema to be validated, a documentation of use, and a minimal example asset. +- A submission must include addition to Compliance Checker and any other supplementary conversion tools within the repository, which allows the use of new schema to be validated. A submission must also include documentation of use and a minimal example asset. -#### 4.1.1 General Extension Schema Rules +#### 4.2.1 General Extension Schema Rules Additional schemas are to be defined through extensions, chiefly for sensors and controls. They must follow these general rules: * **Use of Native Schemas:** Schema definitions must leverage core OpenUSD primitives to prevent attribute duplication. For example, `SensorCameraAPI` must apply to a `UsdGeomCamera` to append digital hardware metadata while natively reusing its optical properties. If no native analogue exists, schemas must be applied to a standard `UsdGeomXform`. * **Separation of Transport:** Extension schemas must not include metadata to handle ROS communication (e.g., topic names, QoS). Instead, they should utilize relationships to target distinct transport prims (e.g., `RosTopicAPI`) to expose their data or commands. +* **Deprecation Policy:** If the core OpenUSD specification formally ratifies an equivalent schema, the corresponding extension schema will be deprecated. Tooling will subsequently migrate assets to the official core standard. + +#### 4.2.2 Physics Schemas + +To leverage emerging simulation features without violating vendor-neutrality (Section 1.4), the registry will host physics extension schemas based on upstream proposals (e.g., from Linux Foundation Newton USD Schemas[NEWTON-SCHEMAS] or AOUSD working groups), as "Incubating Schemas". These schemas must adhere to the following rules: -#### 4.1.2 Control Schemas +* **Namespace:** To prevent collisions with core OpenUSD updates, incubating physics schemas must use the `ExtendedPhysics` class prefix and the `ext_physics:` property prefix. Vendor prefixes (e.g., `newton:`) and core prefixes (e.g., `physics:`) are prohibited. +* **Translation:** OpenUSD does not natively support schema aliasing. Assets generated by tools using vendor-specific staging schemas must be processed via ecosystem tooling (e.g., automated compliance fixers) to replace them with their `ExtendedPhysics*` equivalents prior to distribution. + + +#### 4.2.3 Control Schemas In addition to general extension schema rules, control interfaces and controllers must follow these rules: * **Explicit Targeting:** Controllers should be decoupled from the physical rigid-body hierarchy: authors should place them on dedicated logical prims (e.g., `/Robot/Controllers`) and explicitly target their actuated mechanisms. Simulators must not rely on Xform scene graph nesting to infer a controller's scope. Controllers must declare targets using OpenUSD relationships (`rel`) or standard `UsdCollectionAPI` collections. * **Actuation via Physics:** Control schemas should interface with dynamic bodies strictly through the simulation's physics pipeline. Position, velocity, and effort targets must be routed through normative OpenUSD dynamics paradigms (e.g., `UsdPhysicsDriveAPI`) or universally ratified extension schemas, deferring to isolated vendor extensions only when a ratified standard for the required actuation modality does not exist. Controllers that directly manipulate spatial transforms should only actuate prims where `physics:kinematicEnabled = true`. Control schemas should not handle simulator-level state changes (e.g., native simulator state APIs or ROS `simulation_interfaces`), including resets for RL training or entity state manipulation. * **Runtime selection:** A single asset may contain multiple, mutually exclusive control paradigms for the same hardware (e.g., trajectory control vs. direct effort control). While `VariantSets` remain the standard for structural hardware changes, simulators should provide dynamic lifecycle management of controllers to support runtime switching. The asset's authored state must prevent write conflicts at load time by ensuring controllers actuating the same targets are not simultaneously active (e.g., via a `bool control:starts_enabled` schema property). -#### 4.1.3 Sensor Schemas +#### 4.2.4 Sensor Schemas In addition to general extension schema rules, sensor schemas must follow these rules: * **Ground Truth:** Sensor schemas must emulate measurable phenomena to ensure valid Software-in-the-Loop (SiL) testing. Simulator-generated Ground Truth artifacts (e.g., semantic segmentations, bounding boxes) must not be bundled into physical sensor schemas; they should be explicitly requested via dedicated annotator schemas. * **Traversal:** Sensor schemas must be applied directly to the `UsdGeomXform` or `UsdGeomCamera` defining their physical origin and local coordinate frame. To ensure efficient parser discovery, these prims must reside in the asset's lightweight, traversable kinematic hierarchy. * **Graceful Degradation:** Sensor schemas must define a functional, universal baseline of parameters. Advanced, engine-specific behaviors (e.g., proprietary rendering profiles, custom noise models) must be authored exclusively via vendor-namespaced custom attributes (e.g., `isaac:`, `gazebo:`). Simulators must safely ignore unrecognized namespaces and gracefully fall back to the universal baseline. -### 4.2 Compliant Assets +### 4.3 Compliant Assets -A canonincal repository of open-source, compliant simulation assets is to be established as `ros-simulation/openusd-assets`. These assets will have payloads hosted independently (e.g. in a dedicated repository such as Hugging Face) and must pass the Compliance Checker. +A canonical repository of open-source, compliant simulation assets is to be established as `ros-simulation/openusd-assets`. These assets will have payloads hosted independently (e.g. in a dedicated repository such as Hugging Face) and must pass the Compliance Checker. ## Tools -### Core Schema Definition -The normative OpenUSD schema definition for all `Ros*API` schemas is provided in `schema/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. +The following tools will be provided within `ros-simulation/openusd-schemas` repository alongside core and extension schemas: ### Compliance Checker A REP-XXXX compliance checker is to be developed and shared with the community. The tool will provide validation of all REP recommendations for OpenUSD assets and supply actionable feedback for the user for every violation or non-conformance. +### Supplementary migration tools + +A compliance fixer (e.g., `rep_sanitizer`) will be provider for common issues that can be handled by automated scripting, including: + +* **Schema Translation:** Stripping proprietary staging schemas and replacing them with their neutral `ExtendedPhysics` equivalents (see Section 4.2.2). +* **Transform Standardization:** Automatically decomposing baked 4x4 CAD matrices (`xformOp:transform`) into the mandated `translate` and `orient` operations (Section 1.1). +* **Vendor Isolation:** Scanning for and extracting engine-specific properties (e.g., `isaac:`, `mujoco:`) from the baseline payload into isolated proprietary overlays (Section 1.4). + ## References * **[NVIDIA-ETL-PIPELINE]** NVIDIA, Intrinsic, Disney Research. "Using OpenUSD for Modular and Scalable Robotic Simulation and Development". URL: `https://developer.nvidia.com/blog/using-openusd-for-modular-and-scalable-robotic-simulation-and-development/` @@ -412,6 +429,7 @@ A REP-XXXX compliance checker is to be developed and shared with the community. * **[REP-2003]** ROS Enhancement Proposal 2003, "Sensor Data and Map QoS Settings". * **[GLTF-2.0]** Khronos Group, "glTF 2.0 Specification". * **[GLTF-EXT-INSTANCING]** Khronos Group, "EXT_mesh_gpu_instancing Extension Specification". +* **[NEWTON-SCHEMAS]** Linux Foundation Newton Project. "Newton USD Schemas". URL: `https://github.com/newton-physics/newton-usd-schemas` ## Copyright This document will be placed in the public domain upon being submitted as PR to a REP proposal by original authors. This text will be changed to "This document is placed in the public domain". From d2e69c4b764c0ff93f7196e073c2413d87f584df Mon Sep 17 00:00:00 2001 From: Adam Dabrowski Date: Tue, 28 Apr 2026 14:50:13 +0200 Subject: [PATCH 093/111] Schemas adapted from Newton Signed-off-by: Adam Dabrowski --- extensions/physics/NOTICE | 7 + extensions/physics/README.md | 12 +- extensions/physics/schema.usda | 255 +++++++++++++++++++++++++++++++++ 3 files changed, 263 insertions(+), 11 deletions(-) create mode 100644 extensions/physics/NOTICE diff --git a/extensions/physics/NOTICE b/extensions/physics/NOTICE new file mode 100644 index 0000000..acb91f4 --- /dev/null +++ b/extensions/physics/NOTICE @@ -0,0 +1,7 @@ +Multiple schemas in schema.usda were adapted from Newton: https://github.com/newton-physics/newton-usd-schemas + +Changes include: +- Selection of schemas (omitting solver-specific, global parameters, and control-related). +- Renaming Newton to ExtendedPhysics, newton: to ext_physics: +- Adding sub-namespaces within (e.g. ext_physics:mimic) +- Adjusting some comments. \ No newline at end of file diff --git a/extensions/physics/README.md b/extensions/physics/README.md index b0f0aad..a1283da 100644 --- a/extensions/physics/README.md +++ b/extensions/physics/README.md @@ -1,13 +1,3 @@ # Extended Physics Schema -This schema provides an extended feature set for OpenUSD physics. It draws inspiration from work on [Newton Schemas](https://github.com/newton-physics/newton-usd-schemas), but ensures neutral naming and focus on full interoperabilty. - - -## Mimic Joints - -Joints whose position is a linear function of another joint (e.g., parallel gripper fingers, coupled mechanisms) must declare the coupling declaratively using `ExtendedPhysicsMimicJointAPI`, a **SingleApply** API schema applied to the follower joint. `ExtendedPhysicsMimicJointAPI` must only be applied to `UsdPhysicsRevoluteJoint` or `UsdPhysicsPrismaticJoint` prims. The coupling operates on the joint's native positional value. -* `rel mimic:joint`: Relationship to the source joint. Must use a USD relationship (not a string attribute) to ensure correct path remapping under composition arcs. Mimic relationships must form a Directed Acyclic Graph (DAG); chained couplings are valid, but cycles are prohibited. -* `float mimic:multiplier` (Default: `1.0`): Scale factor. `follower_position = multiplier * source_position + offset`. -* `float mimic:offset` (Default: `0.0`): Constant offset in the source joint's native units. -* *Note: UsdPhysics does not currently provide a joint coupling mechanism. This schema fills that gap. Should AOUSD/ASWF standardize an equivalent under `UsdPhysics`, this REP would adopt the upstream schema.* - +This schema provides an extended feature set for OpenUSD physics. It draws heavily from work on [Newton Schemas](https://github.com/newton-physics/newton-usd-schemas) while ensuring neutral naming and focus on full interoperabilty. diff --git a/extensions/physics/schema.usda b/extensions/physics/schema.usda index e69de29..dd76a64 100644 --- a/extensions/physics/schema.usda +++ b/extensions/physics/schema.usda @@ -0,0 +1,255 @@ +#usda 1.0 +( + "Extended Physics Schemas for OpenUSD Simulation Asset Interoperability." + " Defines declarative, engine-agnostic physics features, " + " meant to extend OpenUSD Physics while following REP-XXXX rules." + subLayers = [ + @usd/schema.usda@ + ] +) + +# ====================================================================== +# Extended Physics Schemas +# +# Physics extension schemas are leveraging emerging simulation features +# without violating vendor-neutrality. They are meant to be +# "Incubating Schemas", based on upstream proposals and pending inclusion +# into the OpenUSD standard. +# ====================================================================== + +# Schemas adapted from Newton upstream: https://github.com/newton-physics/newton-usd-schemas + +class ExtendedPhysicsMaterialAPI "ExtendedPhysicsMaterialAPI" ( + apiSchemas = ["PhysicsMaterialAPI"] + doc = """ExtendedPhysicsMaterialAPI applies on top of a Material, providing extra physical material attributes. + + By applying this schema, the prim also inherits the `PhysicsMaterialAPI` schema.""" +) +{ + float ext_physics:material:torsionalFriction = 0.25 ( + doc = """Torsional friction coefficient (resistance to spinning at a contact point). + + Range: [0, inf) + Units: dimensionless""" + limits = { + dictionary hard = { + float minimum = 0 + } + } + ) + + float ext_physics:material:rollingFriction = 0.0005 ( + doc = """Rolling friction coefficient (resistance to rolling motion). + + Range: [0, inf) + Units: dimensionless""" + limits = { + dictionary hard = { + float minimum = 0 + } + } + ) +} + +class ExtendedPhysicsMimicAPI "ExtendedPhysicsMimicAPI" ( + doc = """ExtendedPhysicsMimicAPI applies on top of a PhysicsJoint, adding additional constraints to mimic the DOFs of another joint. + + A mimic constraint enforces that `joint0 = offset + multiplier * joint1` for the joint DOFs, + where `joint0` is this joint (the follower) and `joint1` (the leader) is specified via the `ext_physics:mimic:joint` relationship. + + The behavior on multi-DOF joints is undefined. The mimic constraint will be applied to each DOF independently, + but as the coefficients are shared across all DOFs, the units for translational and rotational DOFs will be mixed. + Therefore, it is recommended to only use this API on single-DOF joints. + """ +) +{ + bool ext_physics:mimic:enabled = true ( + doc = """Whether the mimic constraint is active. + + When disabled, the follower joint moves independently, as though the mimic constraint was not applied.""" + ) + + rel ext_physics:mimic:joint ( + doc = "Joint that will be mimicked." + ) + + float ext_physics:mimic:offset = 0.0 ( + doc = """Offset added after scaling the leader joint's position/angle. + + Range: (-inf, inf) + Units: distance or degrees (matches the joint type for single-DOF joints)""" + ) + + float ext_physics:mimic:multiplier = 1.0 ( + doc = """Scale factor applied to the leader joint's position/angle. + + A value of 1.0 means the follower tracks the leader exactly (plus `ext_physics:mimic:offset`), + while negative values reverse the direction. + + Range: (-inf, inf) + Units: dimensionless""" + ) +} + + +class ExtendedPhysicsActuatorAPI "ExtendedPhysicsActuatorAPI" ( + doc = """Defines a physical actuator that computes effort to apply to a joint. + + An actuator computes effort (i.e. force/torque for linear/rotational actuators) to apply + to a PhysicsRevoluteJoint or PhysicsPrismaticJoint specified via the `ext_physics:actuator:targets` + relationship. Future versions may expand the set of valid target types. + + Control schemas should use it to drive the actuator, + and limits are applied through `ExtendedPhysicsActuatorClampingBaseAPI`. + + Note: Extended Physics actuators use radians, diverging from UsdPhysicsDriveAPI which uses degrees. + Actuator attributes are also documented in joint space, though this is not enforced, + and users may scale attributes to fit their own convention by updating their parser + and/or integration code accordingly. + + + """ +) +{ + rel ext_physics:actuator:targets ( + doc = """The joint driven by this actuator. + + The relationship must be authored. Parsers should raise an error if no target + is provided; users should deactivate the prim if they want to disable the actuator. + + Currently only the first target is honored, and it must identify either a + `PhysicsRevoluteJoint` or `PhysicsPrismaticJoint`. + + Multi-DOF PhysicsJoints are not supported, even when locked via LimitAPIs to a single axis. + """ + ) +} + +class ExtendedPhysicsActuatorClampingBaseAPI "ExtendedPhysicsActuatorClampingBaseAPI" ( + doc = """Base API for all actuator clamping strategies. + + Any number of ExtendedPhysicsActuatorClampingBaseAPI derived schemas + (e.g. ExtendedPhysicsMaxEffortClampingAPI) may be applied to a ExtendedPhysicsActuator + to constrain actuator output effort (i.e. force/torque for linear/rotational actuators). + The order of clamping is not guaranteed to be preserved thus clamping operations must be order independent. + + Check prim.HasAPI('ExtendedPhysicsActuatorClampingBaseAPI') to detect whether any clamping is present. + """ +) +{ +} + +class ExtendedPhysicsMaxEffortClampingAPI "ExtendedPhysicsMaxEffortClampingAPI" ( + apiSchemas = ["ExtendedPhysicsActuatorClampingBaseAPI"] + doc = """Symmetric clamp on actuator output effort. + + Clamps the actuator output to the range [-maxEffort, +maxEffort]. + """ +) +{ + float ext_physics:clamp_effort:maxEffort = inf ( + doc = """Maximum output effort limit (in joint space). + + The actuator output is clamped to the range [-maxEffort, +maxEffort]. + + Range: [0, inf) + Units: force or torque""" + limits = { + dictionary hard = { + float minimum = 0 + } + } + ) +} + +class ExtendedPhysicsDCMotorClampingAPI "ExtendedPhysicsDCMotorClampingAPI" ( + apiSchemas = ["ExtendedPhysicsActuatorClampingBaseAPI"] + doc = """DC motor four-quadrant effort clamp. + + A four-quadrant effort clamp based on the DC motor effort-speed characteristic: + + effort_max(vel) = min(saturationEffort * (1 - vel / velocityLimit), maxMotorEffort) + effort_min(vel) = max(saturationEffort * (-1 - vel / velocityLimit), -maxMotorEffort) + + At zero velocity the motor can produce up to saturationEffort (capped by maxMotorEffort). + As velocity approaches velocityLimit, available effort drops to zero in both directions. + """ +) +{ + float ext_physics:clamp_motor:maxEffort = inf ( + doc = """Effort limit for the effort-speed curve (in joint space). + + Caps the velocity-dependent effort envelope. + + Range: [0, inf) + Units: force or torque""" + limits = { + dictionary hard = { + float minimum = 0 + } + } + ) + + float ext_physics:clamp_motor:saturationEffort = inf ( + doc = """Peak motor effort at stall (zero velocity). + + This is the maximum effort the motor can produce when not spinning, + before being capped by maxEffort. + + Range: [0, inf) + Units: force or torque""" + limits = { + dictionary hard = { + float minimum = 0 + } + } + ) + + float ext_physics:clamp_motor:velocityLimit = inf ( + doc = """Maximum no-load joint velocity for the effort-speed curve. + + At this velocity, the motor can produce zero effort in the direction + of motion due to losses such as back-EMF. A value of inf disables the effort-speed + saturation effect. + + Range: (0, inf) + Units: distance / seconds or radians / seconds""" + limits = { + dictionary hard = { + float minimum = 0 + } + } + ) +} + +class ExtendedPhysicsPositionBasedClampingAPI "ExtendedPhysicsPositionBasedClampingAPI" ( + apiSchemas = ["ExtendedPhysicsActuatorClampingBaseAPI"] + doc = """Position-dependent effort clamping via lookup table. + + Provides position-dependent effort limits interpolated from a lookup table + to model actuators whose maximum output effort varies with joint position. + + Sampling rules: + - Inputs strictly between adjacent (position, effort) entries are linearly interpolated. + - Inputs at or below ext_physics:clamp_position:lookupPositions[0] clamp to ext_physics:clamp_position:lookupEfforts[0]. + - Inputs at or above ext_physics:clamp_position:lookupPositions[-1] clamp to ext_physics:clamp_position:lookupEfforts[-1]. + - For rotational actuators, positions do not wrap periodically. + """ +) +{ + float[] ext_physics:clamp_position:lookupPositions = [] ( + doc = """Sorted joint positions for the effort lookup table. + + Must be monotonically increasing and the same length as ext_physics:clamp_position:lookupEfforts. + + Units: distance or radians""" + ) + + float[] ext_physics:clamp_position:lookupEfforts = [] ( + doc = """Maximum output effort values corresponding to each entry in ext_physics:clamp_position:lookupPositions. + + Must be the same length as ext_physics:clamp_position:lookupPositions. + + Units: force or torque""" + ) +} From 3ad6c953ff26cac5fb81c70d28b1c18ef3b37925 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Tue, 28 Apr 2026 15:37:13 +0200 Subject: [PATCH 094/111] make schema.usda buildable with usdGenSchema MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Newton schemas are actually generatedSchema.usda, which is not valid input to `usdGenSchema` Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- extensions/physics/schema.usda | 70 +++++++++++++++++++++++++++------- 1 file changed, 57 insertions(+), 13 deletions(-) diff --git a/extensions/physics/schema.usda b/extensions/physics/schema.usda index dd76a64..4ee9df2 100644 --- a/extensions/physics/schema.usda +++ b/extensions/physics/schema.usda @@ -8,6 +8,15 @@ ] ) +over "GLOBAL" ( + customData = { + string libraryName = "usdExtendedPhysics" + string libraryPath = "usdExtendedPhysics" + } +) +{ +} + # ====================================================================== # Extended Physics Schemas # @@ -19,8 +28,13 @@ # Schemas adapted from Newton upstream: https://github.com/newton-physics/newton-usd-schemas -class ExtendedPhysicsMaterialAPI "ExtendedPhysicsMaterialAPI" ( - apiSchemas = ["PhysicsMaterialAPI"] +class "ExtendedPhysicsMaterialAPI" ( + inherits = + customData = { + string className = "MaterialAPI" + token apiSchemaType = "singleApply" + } + prepend apiSchemas = ["PhysicsMaterialAPI"] doc = """ExtendedPhysicsMaterialAPI applies on top of a Material, providing extra physical material attributes. By applying this schema, the prim also inherits the `PhysicsMaterialAPI` schema.""" @@ -51,7 +65,12 @@ class ExtendedPhysicsMaterialAPI "ExtendedPhysicsMaterialAPI" ( ) } -class ExtendedPhysicsMimicAPI "ExtendedPhysicsMimicAPI" ( +class "ExtendedPhysicsMimicAPI" ( + inherits = + customData = { + string className = "MimicAPI" + token apiSchemaType = "singleApply" + } doc = """ExtendedPhysicsMimicAPI applies on top of a PhysicsJoint, adding additional constraints to mimic the DOFs of another joint. A mimic constraint enforces that `joint0 = offset + multiplier * joint1` for the joint DOFs, @@ -92,7 +111,12 @@ class ExtendedPhysicsMimicAPI "ExtendedPhysicsMimicAPI" ( } -class ExtendedPhysicsActuatorAPI "ExtendedPhysicsActuatorAPI" ( +class "ExtendedPhysicsActuatorAPI" ( + inherits = + customData = { + string className = "ActuatorAPI" + token apiSchemaType = "singleApply" + } doc = """Defines a physical actuator that computes effort to apply to a joint. An actuator computes effort (i.e. force/torque for linear/rotational actuators) to apply @@ -125,11 +149,16 @@ class ExtendedPhysicsActuatorAPI "ExtendedPhysicsActuatorAPI" ( ) } -class ExtendedPhysicsActuatorClampingBaseAPI "ExtendedPhysicsActuatorClampingBaseAPI" ( +class "ExtendedPhysicsActuatorClampingBaseAPI" ( + inherits = + customData = { + string className = "ActuatorClampingBaseAPI" + token apiSchemaType = "singleApply" + } doc = """Base API for all actuator clamping strategies. - Any number of ExtendedPhysicsActuatorClampingBaseAPI derived schemas - (e.g. ExtendedPhysicsMaxEffortClampingAPI) may be applied to a ExtendedPhysicsActuator + Any number of ExtendedPhysicsActuatorClampingBaseAPI derived schemas + (e.g. ExtendedPhysicsMaxEffortClampingAPI) may be applied to an ExtendedPhysicsActuatorAPI to constrain actuator output effort (i.e. force/torque for linear/rotational actuators). The order of clamping is not guaranteed to be preserved thus clamping operations must be order independent. @@ -139,8 +168,13 @@ class ExtendedPhysicsActuatorClampingBaseAPI "ExtendedPhysicsActuatorClampingBas { } -class ExtendedPhysicsMaxEffortClampingAPI "ExtendedPhysicsMaxEffortClampingAPI" ( - apiSchemas = ["ExtendedPhysicsActuatorClampingBaseAPI"] +class "ExtendedPhysicsMaxEffortClampingAPI" ( + inherits = + customData = { + string className = "MaxEffortClampingAPI" + token apiSchemaType = "singleApply" + } + prepend apiSchemas = ["ExtendedPhysicsActuatorClampingBaseAPI"] doc = """Symmetric clamp on actuator output effort. Clamps the actuator output to the range [-maxEffort, +maxEffort]. @@ -162,8 +196,13 @@ class ExtendedPhysicsMaxEffortClampingAPI "ExtendedPhysicsMaxEffortClampingAPI" ) } -class ExtendedPhysicsDCMotorClampingAPI "ExtendedPhysicsDCMotorClampingAPI" ( - apiSchemas = ["ExtendedPhysicsActuatorClampingBaseAPI"] +class "ExtendedPhysicsDCMotorClampingAPI" ( + inherits = + customData = { + string className = "DCMotorClampingAPI" + token apiSchemaType = "singleApply" + } + prepend apiSchemas = ["ExtendedPhysicsActuatorClampingBaseAPI"] doc = """DC motor four-quadrant effort clamp. A four-quadrant effort clamp based on the DC motor effort-speed characteristic: @@ -222,8 +261,13 @@ class ExtendedPhysicsDCMotorClampingAPI "ExtendedPhysicsDCMotorClampingAPI" ( ) } -class ExtendedPhysicsPositionBasedClampingAPI "ExtendedPhysicsPositionBasedClampingAPI" ( - apiSchemas = ["ExtendedPhysicsActuatorClampingBaseAPI"] +class "ExtendedPhysicsPositionBasedClampingAPI" ( + inherits = + customData = { + string className = "PositionBasedClampingAPI" + token apiSchemaType = "singleApply" + } + prepend apiSchemas = ["ExtendedPhysicsActuatorClampingBaseAPI"] doc = """Position-dependent effort clamping via lookup table. Provides position-dependent effort limits interpolated from a lookup table From 4302749e0e3b96126cad1bf59164c7c177b21e00 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Wed, 29 Apr 2026 12:17:12 +0200 Subject: [PATCH 095/111] Apply suggestions from code review MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- extensions/physics/README.md | 2 +- rep.md | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/extensions/physics/README.md b/extensions/physics/README.md index a1283da..4815400 100644 --- a/extensions/physics/README.md +++ b/extensions/physics/README.md @@ -1,3 +1,3 @@ # Extended Physics Schema -This schema provides an extended feature set for OpenUSD physics. It draws heavily from work on [Newton Schemas](https://github.com/newton-physics/newton-usd-schemas) while ensuring neutral naming and focus on full interoperabilty. +This schema provides an extended feature set for OpenUSD physics. It draws heavily from work on [Newton Schemas](https://github.com/newton-physics/newton-usd-schemas) while ensuring neutral naming and focus on full interoperability. diff --git a/rep.md b/rep.md index e1d941b..aaeb174 100644 --- a/rep.md +++ b/rep.md @@ -134,7 +134,7 @@ OpenUSD's native instancing mechanisms are designed for repetitive visual and st * *Kinematic Bodies:* Moving bodies that are animated but not dynamically driven by physics should set the physics:kinematicEnabled attribute to true. * *Dummy Frames:* Non-physical dummy frames (e.g., `camera_optical_frame`) must not possess a `PhysicsRigidBodyAPI`. They should be tracked using the `RosFrameAPI` as defined in Section 2.8. * **Inertia Representation:** Unlike URDF and SDFormat's 6-value symmetric matrix, OpenUSD requires an eigendecomposed inertia tensor. Converters must mathematically decompose the source matrix into physics:diagonalInertia (eigenvalues) and physics:principalAxes (quaternion). This native decomposed form is the strict single source of truth; custom 6-value array attributes must not be authored or parsed. -* **Extended Physics:** Many physics features are missing in `USDPhysics`, including mimic joints, deformable bodies and advanced friction. Authors must use `ExtendedPhysics*` schemas for interoperability, following Section 4.2.2. When interoperable schema is not available, assets must isolate specific feature, e.g. deformable soft-body physics into a feature layer for specific domain or vendor (see Section 1.2.1). +* **Extended Physics:** Many physics features are missing in `UsdPhysics`, including mimic joints, deformable bodies and advanced friction. Authors must use `ExtendedPhysics*` schemas for interoperability, following Section 4.2.2. When interoperable schema is not available, assets must isolate specific feature, e.g. deformable soft-body physics into a feature layer for specific domain or vendor (see Section 1.2.1). #### 1.3.1 Collisions @@ -360,7 +360,7 @@ OpenUSD and robotics XML formats (URDF, SDF, MJCF) are fundamentally mismatched A canonical repository for core schema, extension schemas and compliance tooling is `ros-simulation/openusd-schemas`. ### 4.1 Core ROS Schema Definition -The normative OpenUSD schema definition for all `Ros*API` schemas is provided in `schema/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. +The normative OpenUSD schema definition for all `Ros*API` schemas is provided in `core/ros/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. ### 4.2 Schema Registry @@ -414,7 +414,7 @@ A REP-XXXX compliance checker is to be developed and shared with the community. ### Supplementary migration tools -A compliance fixer (e.g., `rep_sanitizer`) will be provider for common issues that can be handled by automated scripting, including: +A compliance fixer (e.g., `rep_sanitizer`) will be provided for common issues that can be handled by automated scripting, including: * **Schema Translation:** Stripping proprietary staging schemas and replacing them with their neutral `ExtendedPhysics` equivalents (see Section 4.2.2). * **Transform Standardization:** Automatically decomposing baked 4x4 CAD matrices (`xformOp:transform`) into the mandated `translate` and `orient` operations (Section 1.1). From a82fa819da4b07e26c80a90ccf6be19ada5ed9c4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Micha=C5=82=20Pe=C5=82ka?= Date: Tue, 28 Apr 2026 14:26:46 +0200 Subject: [PATCH 096/111] Broken down monohlitic controller schema to indivdual controllers. MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Michał Pełka Signed-off-by: Adam Dabrowski --- extensions/control/control_extension.md | 119 ------- extensions/control/schema/schema.usda | 325 ------------------ extensions/external_controller/README.md | 18 + .../external_controller/schema/schema.usda | 43 +++ extensions/integrated_controllers/README.md | 36 ++ .../diff_drive_controller/README.md | 26 ++ .../diff_drive_controller/schema/schema.usda | 126 +++++++ .../README.md | 15 + .../schema/schema.usda | 58 ++++ .../joint_trajectory_controller/README.md | 20 ++ .../schema/schema.usda | 83 +++++ .../rigid_body_controller/README.md | 16 + .../rigid_body_controller/schema/schema.usda | 57 +++ .../integrated_controllers/schema/schema.usda | 45 +++ 14 files changed, 543 insertions(+), 444 deletions(-) delete mode 100644 extensions/control/control_extension.md delete mode 100644 extensions/control/schema/schema.usda create mode 100644 extensions/external_controller/README.md create mode 100644 extensions/external_controller/schema/schema.usda create mode 100644 extensions/integrated_controllers/README.md create mode 100644 extensions/integrated_controllers/diff_drive_controller/README.md create mode 100644 extensions/integrated_controllers/diff_drive_controller/schema/schema.usda create mode 100644 extensions/integrated_controllers/joint_state_broadcaster_controller/README.md create mode 100644 extensions/integrated_controllers/joint_state_broadcaster_controller/schema/schema.usda create mode 100644 extensions/integrated_controllers/joint_trajectory_controller/README.md create mode 100644 extensions/integrated_controllers/joint_trajectory_controller/schema/schema.usda create mode 100644 extensions/integrated_controllers/rigid_body_controller/README.md create mode 100644 extensions/integrated_controllers/rigid_body_controller/schema/schema.usda create mode 100644 extensions/integrated_controllers/schema/schema.usda diff --git a/extensions/control/control_extension.md b/extensions/control/control_extension.md deleted file mode 100644 index 80c4463..0000000 --- a/extensions/control/control_extension.md +++ /dev/null @@ -1,119 +0,0 @@ -# REP XXXX -- OpenUSD Conventions for Simulation Asset Interoperability - Control Extension - -## Abstract - -This document defines conventions for simulating robotic systems in OpenUSD, with a focus on control interfaces and integration with ROS 2. -It proposes standardized API schemas for exposing robot control interfaces to external control algorithms and for instantiating robot controllers directly within the simulated scene. -The goal is to enable modular and scalable robotic simulation that can be easily integrated with ROS 2-based control frameworks. - -## 1. Controllers - -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. - - -### 1.1 External Control Interfaces - -The ROS 2 external control `RosControlExternalAPI` 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. - -### 1.2 Integrated Controller Simulation - -`RosControlIntegratedAPI` allows instantiating robot controllers directly in the simulated scene. -It must reference one or more prims that have [RosTopicAPI](../rep.md#24-topic-interface-rostopicapi), [RosServiceAPI](../rep.md#25-service-interface-rosserviceapi) or [RosActionAPI](../rep.md#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::RosCustomTwistControllerAPI` which will include as built-in `RosControlIntegratedAPI` 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`. - -### 1.2.1 Built-in Controllers - -The following schemas are built-in controller schemas that include `RosControlIntegratedAPI` as a built-in via `prepend apiSchemas`. -Simulators may implement these schemas to provide a standardized control interface for common use cases. -Such usecase can be different robot locomotion (e.g. Ackermann car-like robot) or application specific interfaces (e.g., joint control interface for robot policy). -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 four 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. - -#### 1.2.1.1 RosControlRigidBodyTwistAPI - -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. -This implementation provides a general-purpose controller for applying velocity to a rigid body in a generalized manner. -- `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. - -#### 1.2.1.2 RosControlDiffDriveAPI - -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`: relationship targeting a prim with the RosTopicAPI with `role="subscription"` that provides the velocity commands for this controller. - -- `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. Exposed as dynamic parameter. -- `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². - -#### 1.2.1.3 RosControlJointTrajectoryAPI - -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 `UsdPhysicsJoint`. -- `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. Exposed as dynamic parameter. -- `double ros:joint_trajectory:timeout`: Maximum time allowed to reach the trajectory goal. - -#### 1.2.1.4 RosControlJointStateBroadcasterAPI - -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 joints in the simulator to those in robot description or application. - -- `rel ros:joint_state_broadcaster:publisher`: relationship targeting a prim with the RosTopicAPI with `role="publisher"` for joint state data. -- `rel ros:joint_state_broadcaster:joints`: References to prims with `UsdPhysicsJoint` representing the joints whose states are to be broadcast. -- `string ros:joint_state_broadcaster:frame_id`: The TF frame ID to be used in the published JointState messages. - -## Tools - -### Schema Definition -The normative OpenUSD schema definition for all `RosControl*API` schemas is provided in `schema/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. - diff --git a/extensions/control/schema/schema.usda b/extensions/control/schema/schema.usda deleted file mode 100644 index cbca7ec..0000000 --- a/extensions/control/schema/schema.usda +++ /dev/null @@ -1,325 +0,0 @@ -#usda 1.0 -( - "ROS Integration Schemas for OpenUSD Simulation Asset Interoperability." - " Defines declarative, engine-agnostic API schemas for ROS interfaces" - " as specified in REP-XXXX, Section 2." - subLayers = [ - @usd/schema.usda@ - ] -) - -over "GLOBAL" ( - customData = { - string libraryName = "usdRosControl" - string libraryPath = "usdRosControl" - string libraryPrefix = "usdRosControl" - dictionary libraryTokens = { - } - } -) -{ -} - -# ====================================================================== -# Robot Control Schemas -# Two approaches to simulating a robotic system are defined: -# -# Control-level simulation (Section 1.1): -# The simulator exposes joint state and command interfaces to an -# external control algorithm. The interface shape is simulator- -# specific (e.g. ros2_control hardware_interface, IPC, HIL). -# Prims are marked with RosControlExternalAPI as a built-in. -# -# Application-level (integrated) simulation (Section 1.2): -# The controller runs inside the simulator and is configured via -# prim parameters and ROS communication. Prims are marked with -# RosControlIntegratedAPI as a built-in and reference topic, -# service, or action interface prims. -# ====================================================================== - -# ====================================================================== -# Section 1.1 - RosControlExternalAPI -# ====================================================================== - -class "RosControlExternalAPI" ( - inherits = - customData = { - token apiSchemaType = "singleApply" - string className = "RosControlExternalAPI" - } - doc = """Base schema for exposing robot control interfaces to external control algorithms. - - Applied (via 'prepend apiSchemas') by simulator-specific schemas to - identify prims whose joint state and command interfaces should be - exposed to an external control entity (e.g. a ros2_control - hardware_interface plugin, an inter-process controller, or a - hardware-in-the-loop connection). - """ -) -{ -} - -# ====================================================================== -# Section 1.2 - RosControlIntegratedAPI -# ====================================================================== - -class "RosControlIntegratedAPI" ( - inherits = - customData = { - token apiSchemaType = "singleApply" - string className = "RosControlIntegratedAPI" - } - doc = """Base schema for integrated (application-level) robot controllers. - - Included as a built-in via 'prepend apiSchemas' by simulator-specific - or standardized controller schemas that run the controller logic - inside the simulator. All prims referenced by a controller that - inherits this schema must have at least one of RosTopicAPI, - RosServiceAPI, or RosActionAPI applied. USD does not enforce this - constraint at the schema level; simulators are responsible for - runtime validation. - """ -) -{ -} - -# ====================================================================== -# Section 1.2.1.1 - RosControlRigidBodyTwistAPI -# ====================================================================== - -class "RosControlRigidBodyTwistAPI" ( - inherits = - prepend apiSchemas = ["RosControlIntegratedAPI"] - customData = { - token apiSchemaType = "singleApply" - string className = "RosControlRigidBodyTwistAPI" - } - doc = """Controls a rigid body via geometry_msgs/Twist messages. - - Subscribes to a Twist topic and applies the commanded linear and - angular velocities directly to a rigid body in the physics engine, - with optional velocity and acceleration limits. - """ -) -{ - rel ros:rigid_body_twist:subscriber ( - customData = { - string apiName = "subscriber" - } - doc = """Reference to a prim with RosTopicAPI configured as a - subscription for geometry_msgs/Twist control messages.""" - ) - - rel ros:rigid_body_twist:body ( - customData = { - string apiName = "body" - } - doc = """Reference to a prim with UsdPhysicsRigidBodyAPI to which - the commanded velocities are applied.""" - ) -} - -# ====================================================================== -# Section 1.2.1.2 - RosControlDiffDriveAPI -# ====================================================================== - -class "RosControlDiffDriveAPI" ( - inherits = - prepend apiSchemas = ["RosControlIntegratedAPI"] - customData = { - token apiSchemaType = "singleApply" - string className = "RosControlDiffDriveAPI" - } - doc = """Controls a differential drive robot via geometry_msgs/Twist messages. - - Subscribes to a Twist topic, converts commanded linear and angular - velocities into individual wheel velocities, and applies them to - wheel joint prims with UsdPhysicsDriveAPI. Publishes odometry data - as nav_msgs/Odometry. Implementation should follow logic similar to - the diff_drive_controller in ros2_controllers. - """ -) -{ - rel ros:diff_drive:subscriber ( - customData = { - string apiName = "subscriber" - } - doc = """Reference to a prim with RosTopicAPI configured as a - subscription for geometry_msgs/Twist velocity commands.""" - ) - - rel ros:diff_drive:odom ( - customData = { - string apiName = "odom" - } - doc = """Reference to a prim with RosTopicAPI configured as a - publisher for nav_msgs/Odometry data.""" - ) - - rel ros:diff_drive:left_wheels ( - customData = { - string apiName = "leftWheels" - } - doc = """References to prims with UsdPhysicsDriveAPI representing - the left wheel joints.""" - ) - - rel ros:diff_drive:right_wheels ( - customData = { - string apiName = "rightWheels" - } - doc = """References to prims with UsdPhysicsDriveAPI representing - the right wheel joints.""" - ) - - uniform double ros:diff_drive:wheel_separation ( - customData = { - string apiName = "wheelSeparation" - } - doc = """Distance between the left and right wheel contact points - in meters.""" - ) - - uniform double ros:diff_drive:wheel_radius ( - customData = { - string apiName = "wheelRadius" - } - doc = """Radius of the wheels in meters.""" - ) - - uniform double ros:diff_drive:cmd_vel_timeout = 0.5 ( - customData = { - string apiName = "cmdVelTimeout" - } - doc = """Timeout in seconds after which a velocity command is - considered stale and wheel velocities are zeroed.""" - ) - - uniform double ros:diff_drive:linear:x:max_velocity ( - customData = { - string apiName = "linearXMaxVelocity" - } - doc = """Maximum linear velocity along the X axis in m/s.""" - ) - - uniform double ros:diff_drive:linear:x:max_acceleration ( - customData = { - string apiName = "linearXMaxAcceleration" - } - doc = """Maximum linear acceleration along the X axis in m/s².""" - ) - - uniform double ros:diff_drive:angular:z:max_velocity ( - customData = { - string apiName = "angularZMaxVelocity" - } - doc = """Maximum angular velocity around the Z axis in rad/s.""" - ) - - uniform double ros:diff_drive:angular:z:max_acceleration ( - customData = { - string apiName = "angularZMaxAcceleration" - } - doc = """Maximum angular acceleration around the Z axis in rad/s².""" - ) -} - -# ====================================================================== -# Section 1.2.1.3 - RosControlJointTrajectoryAPI -# ====================================================================== - -class "RosControlJointTrajectoryAPI" ( - inherits = - prepend apiSchemas = ["RosControlIntegratedAPI"] - customData = { - token apiSchemaType = "singleApply" - string className = "RosControlJointTrajectoryAPI" - } - doc = """Executes joint trajectories via control_msgs/FollowJointTrajectory actions. - - Accepts action goals and commands the simulator to follow the - specified joint trajectory. Implementation should follow logic - similar to the joint_trajectory_controller in ros2_controllers. - """ -) -{ - rel ros:joint_trajectory:server ( - customData = { - string apiName = "server" - } - doc = """Reference to a prim with RosActionAPI configured as a - server for control_msgs/FollowJointTrajectory action goals.""" - ) - - rel ros:joint_trajectory:command_joints ( - customData = { - string apiName = "commandJoints" - } - doc = """References to prims with UsdPhysicsJoint representing - the joints to be commanded along the trajectory. Simulators must - use the ros:joint:name custom property for joint name mapping, - falling back to the prim name if absent.""" - ) - - uniform double ros:joint_trajectory:action_monitor_rate ( - customData = { - string apiName = "actionMonitorRate" - } - doc = """Frequency in Hz at which trajectory execution progress - is monitored.""" - ) - - uniform double ros:joint_trajectory:stopped_velocity_tolerance ( - customData = { - string apiName = "stoppedVelocityTolerance" - } - doc = """Velocity tolerance at the end of the trajectory below - which the controlled system is considered stopped.""" - ) - - uniform double ros:joint_trajectory:timeout ( - customData = { - string apiName = "timeout" - } - doc = """Maximum time in seconds allowed to reach the trajectory - goal before the action is aborted.""" - ) -} - -# ====================================================================== -# Section 1.2.1.4 - RosControlJointStateBroadcasterAPI -# ====================================================================== - -class "RosControlJointStateBroadcasterAPI" ( - inherits = - prepend apiSchemas = ["RosControlIntegratedAPI"] - customData = { - token apiSchemaType = "singleApply" - string className = "RosControlJointStateBroadcasterAPI" - } - doc = """Reads joint states and publishes them as sensor_msgs/JointState messages. - - Implementation should follow logic similar to the - joint_state_broadcaster in ros2_controllers. - """ -) -{ - rel ros:joint_state_broadcaster:publisher ( - customData = { - string apiName = "publisher" - } - doc = """Reference to a prim with RosTopicAPI configured as a - publisher for sensor_msgs/JointState messages.""" - ) - - rel ros:joint_state_broadcaster:joints ( - customData = { - string apiName = "joints" - } - doc = """References to prims with UsdPhysicsJoint representing - the joints whose states are to be broadcast. Simulators must use - the ros:joint:name custom property for joint name mapping, - falling back to the prim name if absent.""" - ) - -} diff --git a/extensions/external_controller/README.md b/extensions/external_controller/README.md new file mode 100644 index 0000000..0203c2c --- /dev/null +++ b/extensions/external_controller/README.md @@ -0,0 +1,18 @@ +# REP XXXX -- OpenUSD Conventions for Simulation Asset Interoperability - External Controller Extension + +## Abstract + +This document defines conventions for the external control interface in OpenUSD-based robot simulation, where the control algorithm runs outside the simulator. +It enables test scenarios where the simulator provides a physics digital twin of the robot and exposes its low-level hardware interfaces (e.g. joint position, velocity, and effort command interfaces) to an external control entity. + +## External Control Interfaces + +The ROS 2 external control `RosControlExternalAPI` 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 a controller. +A simulator loading a prim with this schema should establish a connection, load a controller plugin, spawn a controller instance, or set up a hardware-in-the-loop connection to the robot controller, +and expose the control and state interfaces to the control entity. + +## Tools + +### Schema Definition +The normative OpenUSD schema definition for `RosControlExternalAPI` is provided in `schema/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. diff --git a/extensions/external_controller/schema/schema.usda b/extensions/external_controller/schema/schema.usda new file mode 100644 index 0000000..a3a4e73 --- /dev/null +++ b/extensions/external_controller/schema/schema.usda @@ -0,0 +1,43 @@ +#usda 1.0 +( + "ROS Integration Schemas for OpenUSD Simulation Asset Interoperability." + " Defines declarative, engine-agnostic API schemas for ROS external" + " control interfaces as specified in REP-XXXX, Section 1.1." + subLayers = [ + @usd/schema.usda@ + ] +) + +over "GLOBAL" ( + customData = { + string libraryName = "usdRosControlExternal" + string libraryPath = "usdRosControlExternal" + string libraryPrefix = "usdRosControlExternal" + dictionary libraryTokens = { + } + } +) +{ +} + +# ====================================================================== +# RosControlExternalAPI +# ====================================================================== + +class "RosControlExternalAPI" ( + inherits = + customData = { + token apiSchemaType = "singleApply" + string className = "RosControlExternalAPI" + } + doc = """Base schema for exposing robot control interfaces to external control algorithms. + + Applied (via 'prepend apiSchemas') by simulator-specific schemas to + identify prims whose joint state and command interfaces should be + exposed to an external control entity (e.g. a ros2_control + hardware_interface plugin, an inter-process controller, or a + hardware-in-the-loop connection). + """ +) +{ +} \ No newline at end of file diff --git a/extensions/integrated_controllers/README.md b/extensions/integrated_controllers/README.md new file mode 100644 index 0000000..037b3cc --- /dev/null +++ b/extensions/integrated_controllers/README.md @@ -0,0 +1,36 @@ +# REP XXXX -- OpenUSD Conventions for Simulation Asset Interoperability - Integrated Control Extension + +## Abstract + +This document defines conventions for simulating robotic systems in OpenUSD using integrated controller algorithms running inside the simulation environment. +This enables application-level testing, where the robotic system is simulated as a whole, including its physical properties, kinematics, and dynamics. +In this approach the controller is integrated in the simulator codebase and managed by parameters of the prim and ROS communication. + +## Integrated Controller Simulation + +`RosControlIntegratedAPI` allows instantiating robot controllers directly in the simulated scene. +It must reference one or more prims that have [RosTopicAPI](../../rep.md#24-topic-interface-rostopicapi), [RosServiceAPI](../../rep.md#25-service-interface-rosserviceapi) or [RosActionAPI](../../rep.md#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. +For example, `simulatorXYZ::RosCustomTwistControllerAPI` would include `RosControlIntegratedAPI` as a built-in and reference prims: +- `RosTopicAPI` for subscription of control messages. +- `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 a controller have at least one of the following API schemas applied: `RosTopicAPI`, `RosServiceAPI` or `RosActionAPI`. + +### Built-in Controllers + +The following schemas are built-in controller schemas that include `RosControlIntegratedAPI` as a built-in via `prepend apiSchemas`. +Simulators may implement these schemas to provide a standardized control interface for common use cases, +such as different robot locomotion paradigms (e.g. Ackermann steering) or application-specific interfaces (e.g. joint control for robot policies). +The following controllers are proposed as a minimal baseline for initial compliance. +The parameters and logic should follow established controllers in the ROS ecosystem and allow bootstrapping robot simulation with minimal custom development. +Simulators may implement additional controllers as needed, but these four are proposed as the baseline for application-level simulation compliance. +The implementation should support multi-robot simulation and control by leveraging namespaces. + +## Controller Schemas + +Individual controllers have their schema definitions in `/schema/schema.usda`. The sibling directories of this file each contain one such controller. + +## Schema Definition + +The OpenUSD schema definition for `RosControlIntegratedAPI` is provided in `schema/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. diff --git a/extensions/integrated_controllers/diff_drive_controller/README.md b/extensions/integrated_controllers/diff_drive_controller/README.md new file mode 100644 index 0000000..05c0ed1 --- /dev/null +++ b/extensions/integrated_controllers/diff_drive_controller/README.md @@ -0,0 +1,26 @@ +# RosControlDiffDriveAPI + +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`: relationship targeting a prim with the RosTopicAPI with `role="subscription"` that provides the velocity commands for this controller. +- `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. Exposed as dynamic parameter. +- `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². + +## Tools + +### Schema Definition +The normative OpenUSD schema definition for `RosControlDiffDriveAPI` is provided in `schema/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. diff --git a/extensions/integrated_controllers/diff_drive_controller/schema/schema.usda b/extensions/integrated_controllers/diff_drive_controller/schema/schema.usda new file mode 100644 index 0000000..bf889b9 --- /dev/null +++ b/extensions/integrated_controllers/diff_drive_controller/schema/schema.usda @@ -0,0 +1,126 @@ +#usda 1.0 +( + "ROS Integration Schemas for OpenUSD Simulation Asset Interoperability." + " Defines declarative, engine-agnostic API schemas for the differential" + " drive controller as specified in REP-XXXX, Section 1.2.1.2." + subLayers = [ + @usd/schema.usda@ + ] +) + +over "GLOBAL" ( + customData = { + string libraryName = "usdRosControlDiffDrive" + string libraryPath = "usdRosControlDiffDrive" + string libraryPrefix = "usdRosControlDiffDrive" + dictionary libraryTokens = { + } + } +) +{ +} + +# ====================================================================== +# RosControlDiffDriveAPI +# ====================================================================== + +class "RosControlDiffDriveAPI" ( + inherits = + prepend apiSchemas = ["RosControlIntegratedAPI"] + customData = { + token apiSchemaType = "singleApply" + string className = "RosControlDiffDriveAPI" + } + doc = """Controls a differential drive robot via geometry_msgs/Twist messages. + + Subscribes to a Twist topic, converts commanded linear and angular + velocities into individual wheel velocities, and applies them to + wheel joint prims with UsdPhysicsDriveAPI. Publishes odometry data + as nav_msgs/Odometry. Implementation should follow logic similar to + the diff_drive_controller in ros2_controllers. + """ +) +{ + rel ros:diff_drive:subscriber ( + customData = { + string apiName = "subscriber" + } + doc = """Reference to a prim with RosTopicAPI configured as a + subscription for geometry_msgs/Twist velocity commands.""" + ) + + rel ros:diff_drive:odom ( + customData = { + string apiName = "odom" + } + doc = """Reference to a prim with RosTopicAPI configured as a + publisher for nav_msgs/Odometry data.""" + ) + + rel ros:diff_drive:left_wheels ( + customData = { + string apiName = "leftWheels" + } + doc = """References to prims with UsdPhysicsDriveAPI representing + the left wheel joints.""" + ) + + rel ros:diff_drive:right_wheels ( + customData = { + string apiName = "rightWheels" + } + doc = """References to prims with UsdPhysicsDriveAPI representing + the right wheel joints.""" + ) + + uniform double ros:diff_drive:wheel_separation ( + customData = { + string apiName = "wheelSeparation" + } + doc = """Distance between the left and right wheel contact points + in meters.""" + ) + + uniform double ros:diff_drive:wheel_radius ( + customData = { + string apiName = "wheelRadius" + } + doc = """Radius of the wheels in meters.""" + ) + + uniform double ros:diff_drive:cmd_vel_timeout = 0.5 ( + customData = { + string apiName = "cmdVelTimeout" + } + doc = """Timeout in seconds after which a velocity command is + considered stale and wheel velocities are zeroed.""" + ) + + uniform double ros:diff_drive:linear:x:max_velocity ( + customData = { + string apiName = "linearXMaxVelocity" + } + doc = """Maximum linear velocity along the X axis in m/s.""" + ) + + uniform double ros:diff_drive:linear:x:max_acceleration ( + customData = { + string apiName = "linearXMaxAcceleration" + } + doc = """Maximum linear acceleration along the X axis in m/s².""" + ) + + uniform double ros:diff_drive:angular:z:max_velocity ( + customData = { + string apiName = "angularZMaxVelocity" + } + doc = """Maximum angular velocity around the Z axis in rad/s.""" + ) + + uniform double ros:diff_drive:angular:z:max_acceleration ( + customData = { + string apiName = "angularZMaxAcceleration" + } + doc = """Maximum angular acceleration around the Z axis in rad/s².""" + ) +} diff --git a/extensions/integrated_controllers/joint_state_broadcaster_controller/README.md b/extensions/integrated_controllers/joint_state_broadcaster_controller/README.md new file mode 100644 index 0000000..7574c4e --- /dev/null +++ b/extensions/integrated_controllers/joint_state_broadcaster_controller/README.md @@ -0,0 +1,15 @@ +# RosControlJointStateBroadcasterAPI + +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#210-custom-names-to-ros-joints) in `ros:joint:name` +property of the joint prims and use it for mapping joints in the simulator to those in robot description or application. + +- `rel ros:joint_state_broadcaster:publisher`: relationship targeting a prim with the RosTopicAPI with `role="publisher"` for joint state data. +- `rel ros:joint_state_broadcaster:joints`: References to prims with `UsdPhysicsJoint` representing the joints whose states are to be broadcast. +- `string ros:joint_state_broadcaster:frame_id`: The TF frame ID to be used in the published JointState messages. + +## Tools + +### Schema Definition +The normative OpenUSD schema definition for `RosControlJointStateBroadcasterAPI` is provided in `schema/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. diff --git a/extensions/integrated_controllers/joint_state_broadcaster_controller/schema/schema.usda b/extensions/integrated_controllers/joint_state_broadcaster_controller/schema/schema.usda new file mode 100644 index 0000000..71fc134 --- /dev/null +++ b/extensions/integrated_controllers/joint_state_broadcaster_controller/schema/schema.usda @@ -0,0 +1,58 @@ +#usda 1.0 +( + "ROS Integration Schemas for OpenUSD Simulation Asset Interoperability." + " Defines declarative, engine-agnostic API schemas for the joint state" + " broadcaster controller as specified in REP-XXXX, Section 1.2.1.4." + subLayers = [ + @usd/schema.usda@ + ] +) + +over "GLOBAL" ( + customData = { + string libraryName = "usdRosControlJointStateBroadcaster" + string libraryPath = "usdRosControlJointStateBroadcaster" + string libraryPrefix = "usdRosControlJointStateBroadcaster" + dictionary libraryTokens = { + } + } +) +{ +} + +# ====================================================================== +# RosControlJointStateBroadcasterAPI +# ====================================================================== + +class "RosControlJointStateBroadcasterAPI" ( + inherits = + prepend apiSchemas = ["RosControlIntegratedAPI"] + customData = { + token apiSchemaType = "singleApply" + string className = "RosControlJointStateBroadcasterAPI" + } + doc = """Reads joint states and publishes them as sensor_msgs/JointState messages. + + Implementation should follow logic similar to the + joint_state_broadcaster in ros2_controllers. + """ +) +{ + rel ros:joint_state_broadcaster:publisher ( + customData = { + string apiName = "publisher" + } + doc = """Reference to a prim with RosTopicAPI configured as a + publisher for sensor_msgs/JointState messages.""" + ) + + rel ros:joint_state_broadcaster:joints ( + customData = { + string apiName = "joints" + } + doc = """References to prims with UsdPhysicsJoint representing + the joints whose states are to be broadcast. Simulators must use + the ros:joint:name custom property for joint name mapping, + falling back to the prim name if absent.""" + ) +} diff --git a/extensions/integrated_controllers/joint_trajectory_controller/README.md b/extensions/integrated_controllers/joint_trajectory_controller/README.md new file mode 100644 index 0000000..c3f2467 --- /dev/null +++ b/extensions/integrated_controllers/joint_trajectory_controller/README.md @@ -0,0 +1,20 @@ +# RosControlJointTrajectoryAPI + +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#210-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 `UsdPhysicsJoint`. +- `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. Exposed as dynamic parameter. +- `double ros:joint_trajectory:timeout`: Maximum time allowed to reach the trajectory goal. + +## Tools + +### Schema Definition +The normative OpenUSD schema definition for `RosControlJointTrajectoryAPI` is provided in `schema/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. diff --git a/extensions/integrated_controllers/joint_trajectory_controller/schema/schema.usda b/extensions/integrated_controllers/joint_trajectory_controller/schema/schema.usda new file mode 100644 index 0000000..8d9ab7b --- /dev/null +++ b/extensions/integrated_controllers/joint_trajectory_controller/schema/schema.usda @@ -0,0 +1,83 @@ +#usda 1.0 +( + "ROS Integration Schemas for OpenUSD Simulation Asset Interoperability." + " Defines declarative, engine-agnostic API schemas for the joint" + " trajectory controller as specified in REP-XXXX, Section 1.2.1.3." + subLayers = [ + @usd/schema.usda@ + ] +) + +over "GLOBAL" ( + customData = { + string libraryName = "usdRosControlJointTrajectory" + string libraryPath = "usdRosControlJointTrajectory" + string libraryPrefix = "usdRosControlJointTrajectory" + dictionary libraryTokens = { + } + } +) +{ +} + +# ====================================================================== +# RosControlJointTrajectoryAPI +# ====================================================================== + +class "RosControlJointTrajectoryAPI" ( + inherits = + prepend apiSchemas = ["RosControlIntegratedAPI"] + customData = { + token apiSchemaType = "singleApply" + string className = "RosControlJointTrajectoryAPI" + } + doc = """Executes joint trajectories via control_msgs/FollowJointTrajectory actions. + + Accepts action goals and commands the simulator to follow the + specified joint trajectory. Implementation should follow logic + similar to the joint_trajectory_controller in ros2_controllers. + """ +) +{ + rel ros:joint_trajectory:server ( + customData = { + string apiName = "server" + } + doc = """Reference to a prim with RosActionAPI configured as a + server for control_msgs/FollowJointTrajectory action goals.""" + ) + + rel ros:joint_trajectory:command_joints ( + customData = { + string apiName = "commandJoints" + } + doc = """References to prims with UsdPhysicsJoint representing + the joints to be commanded along the trajectory. Simulators must + use the ros:joint:name custom property for joint name mapping, + falling back to the prim name if absent.""" + ) + + uniform double ros:joint_trajectory:action_monitor_rate ( + customData = { + string apiName = "actionMonitorRate" + } + doc = """Frequency in Hz at which trajectory execution progress + is monitored.""" + ) + + uniform double ros:joint_trajectory:stopped_velocity_tolerance ( + customData = { + string apiName = "stoppedVelocityTolerance" + } + doc = """Velocity tolerance at the end of the trajectory below + which the controlled system is considered stopped.""" + ) + + uniform double ros:joint_trajectory:timeout ( + customData = { + string apiName = "timeout" + } + doc = """Maximum time in seconds allowed to reach the trajectory + goal before the action is aborted.""" + ) +} diff --git a/extensions/integrated_controllers/rigid_body_controller/README.md b/extensions/integrated_controllers/rigid_body_controller/README.md new file mode 100644 index 0000000..5f97c30 --- /dev/null +++ b/extensions/integrated_controllers/rigid_body_controller/README.md @@ -0,0 +1,16 @@ +# RosControlRigidBodyTwistAPI + +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. +This provides a general-purpose controller for applying velocity commands to a rigid body without wheel kinematics or joint decomposition. + +- `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` to which the commanded velocities are applied. + +## Tools + +### Schema Definition +The normative OpenUSD schema definition for `RosControlRigidBodyTwistAPI` is provided in `schema/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. diff --git a/extensions/integrated_controllers/rigid_body_controller/schema/schema.usda b/extensions/integrated_controllers/rigid_body_controller/schema/schema.usda new file mode 100644 index 0000000..bf101c4 --- /dev/null +++ b/extensions/integrated_controllers/rigid_body_controller/schema/schema.usda @@ -0,0 +1,57 @@ +#usda 1.0 +( + "ROS Integration Schemas for OpenUSD Simulation Asset Interoperability." + " Defines declarative, engine-agnostic API schemas for the rigid body" + " twist controller as specified in REP-XXXX, Section 1.2.1.1." + subLayers = [ + @usd/schema.usda@ + ] +) + +over "GLOBAL" ( + customData = { + string libraryName = "usdRosControlRigidBodyTwist" + string libraryPath = "usdRosControlRigidBodyTwist" + string libraryPrefix = "usdRosControlRigidBodyTwist" + dictionary libraryTokens = { + } + } +) +{ +} + +# ====================================================================== +# RosControlRigidBodyTwistAPI +# ====================================================================== + +class "RosControlRigidBodyTwistAPI" ( + inherits = + prepend apiSchemas = ["RosControlIntegratedAPI"] + customData = { + token apiSchemaType = "singleApply" + string className = "RosControlRigidBodyTwistAPI" + } + doc = """Controls a rigid body via geometry_msgs/Twist messages. + + Subscribes to a Twist topic and applies the commanded linear and + angular velocities directly to a rigid body in the physics engine, + with optional velocity and acceleration limits. + """ +) +{ + rel ros:rigid_body_twist:subscriber ( + customData = { + string apiName = "subscriber" + } + doc = """Reference to a prim with RosTopicAPI configured as a + subscription for geometry_msgs/Twist control messages.""" + ) + + rel ros:rigid_body_twist:body ( + customData = { + string apiName = "body" + } + doc = """Reference to a prim with UsdPhysicsRigidBodyAPI to which + the commanded velocities are applied.""" + ) +} diff --git a/extensions/integrated_controllers/schema/schema.usda b/extensions/integrated_controllers/schema/schema.usda new file mode 100644 index 0000000..c926d3b --- /dev/null +++ b/extensions/integrated_controllers/schema/schema.usda @@ -0,0 +1,45 @@ +#usda 1.0 +( + "ROS Integration Schemas for OpenUSD Simulation Asset Interoperability." + " Defines the base API schema for integrated (application-level) robot" + " controllers as specified in REP-XXXX, Section 1.2." + subLayers = [ + @usd/schema.usda@ + ] +) + +over "GLOBAL" ( + customData = { + string libraryName = "usdRosControl" + string libraryPath = "usdRosControl" + string libraryPrefix = "usdRosControl" + dictionary libraryTokens = { + } + } +) +{ +} + +# ====================================================================== +# RosControlIntegratedAPI +# ====================================================================== + +class "RosControlIntegratedAPI" ( + inherits = + customData = { + token apiSchemaType = "singleApply" + string className = "RosControlIntegratedAPI" + } + doc = """Base schema for integrated (application-level) robot controllers. + + Included as a built-in via 'prepend apiSchemas' by simulator-specific + or standardized controller schemas that run the controller logic + inside the simulator. All prims referenced by a controller that + inherits this schema must have at least one of RosTopicAPI, + RosServiceAPI, or RosActionAPI applied. USD does not enforce this + constraint at the schema level; simulators are responsible for + runtime validation. + """ +) +{ +} From f5f53052b541665dcaa1d51226bd5f9c736b90df Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Wed, 29 Apr 2026 12:19:07 +0200 Subject: [PATCH 097/111] Apply review feedback on controller schemas MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - Move schema.usda up out of schema/ subdirs to follow OpenUSD convention (cf. usdLux) - Rename rigid_body_controller dir to rigid_body_twist_controller for consistency - Drop libraryPrefix (defaults to capitalized libraryName, gives PascalCase C++ class names) - Update README schema-path references accordingly Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- extensions/external_controller/README.md | 2 +- extensions/external_controller/{schema => }/schema.usda | 3 +-- extensions/integrated_controllers/README.md | 4 ++-- .../integrated_controllers/diff_drive_controller/README.md | 2 +- .../diff_drive_controller/{schema => }/schema.usda | 1 - .../joint_state_broadcaster_controller/README.md | 2 +- .../{schema => }/schema.usda | 1 - .../joint_trajectory_controller/README.md | 2 +- .../joint_trajectory_controller/{schema => }/schema.usda | 1 - .../README.md | 2 +- .../schema => rigid_body_twist_controller}/schema.usda | 1 - extensions/integrated_controllers/{schema => }/schema.usda | 1 - 12 files changed, 8 insertions(+), 14 deletions(-) rename extensions/external_controller/{schema => }/schema.usda (95%) rename extensions/integrated_controllers/diff_drive_controller/{schema => }/schema.usda (98%) rename extensions/integrated_controllers/joint_state_broadcaster_controller/{schema => }/schema.usda (96%) rename extensions/integrated_controllers/joint_trajectory_controller/{schema => }/schema.usda (97%) rename extensions/integrated_controllers/{rigid_body_controller => rigid_body_twist_controller}/README.md (77%) rename extensions/integrated_controllers/{rigid_body_controller/schema => rigid_body_twist_controller}/schema.usda (96%) rename extensions/integrated_controllers/{schema => }/schema.usda (96%) diff --git a/extensions/external_controller/README.md b/extensions/external_controller/README.md index 0203c2c..b7a4fbe 100644 --- a/extensions/external_controller/README.md +++ b/extensions/external_controller/README.md @@ -15,4 +15,4 @@ and expose the control and state interfaces to the control entity. ## Tools ### Schema Definition -The normative OpenUSD schema definition for `RosControlExternalAPI` is provided in `schema/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. +The normative OpenUSD schema definition for `RosControlExternalAPI` is provided in `schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. diff --git a/extensions/external_controller/schema/schema.usda b/extensions/external_controller/schema.usda similarity index 95% rename from extensions/external_controller/schema/schema.usda rename to extensions/external_controller/schema.usda index a3a4e73..07ec297 100644 --- a/extensions/external_controller/schema/schema.usda +++ b/extensions/external_controller/schema.usda @@ -12,7 +12,6 @@ over "GLOBAL" ( customData = { string libraryName = "usdRosControlExternal" string libraryPath = "usdRosControlExternal" - string libraryPrefix = "usdRosControlExternal" dictionary libraryTokens = { } } @@ -40,4 +39,4 @@ class "RosControlExternalAPI" ( """ ) { -} \ No newline at end of file +} diff --git a/extensions/integrated_controllers/README.md b/extensions/integrated_controllers/README.md index 037b3cc..835e813 100644 --- a/extensions/integrated_controllers/README.md +++ b/extensions/integrated_controllers/README.md @@ -29,8 +29,8 @@ The implementation should support multi-robot simulation and control by leveragi ## Controller Schemas -Individual controllers have their schema definitions in `/schema/schema.usda`. The sibling directories of this file each contain one such controller. +Individual controllers have their schema definitions in `/schema.usda`. The sibling directories of this file each contain one such controller. ## Schema Definition -The OpenUSD schema definition for `RosControlIntegratedAPI` is provided in `schema/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. +The OpenUSD schema definition for `RosControlIntegratedAPI` is provided in `schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. diff --git a/extensions/integrated_controllers/diff_drive_controller/README.md b/extensions/integrated_controllers/diff_drive_controller/README.md index 05c0ed1..a646172 100644 --- a/extensions/integrated_controllers/diff_drive_controller/README.md +++ b/extensions/integrated_controllers/diff_drive_controller/README.md @@ -23,4 +23,4 @@ Implementation should follow logic similar to the `diff_drive_controller` in `ro ## Tools ### Schema Definition -The normative OpenUSD schema definition for `RosControlDiffDriveAPI` is provided in `schema/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. +The normative OpenUSD schema definition for `RosControlDiffDriveAPI` is provided in `schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. diff --git a/extensions/integrated_controllers/diff_drive_controller/schema/schema.usda b/extensions/integrated_controllers/diff_drive_controller/schema.usda similarity index 98% rename from extensions/integrated_controllers/diff_drive_controller/schema/schema.usda rename to extensions/integrated_controllers/diff_drive_controller/schema.usda index bf889b9..f123dcd 100644 --- a/extensions/integrated_controllers/diff_drive_controller/schema/schema.usda +++ b/extensions/integrated_controllers/diff_drive_controller/schema.usda @@ -12,7 +12,6 @@ over "GLOBAL" ( customData = { string libraryName = "usdRosControlDiffDrive" string libraryPath = "usdRosControlDiffDrive" - string libraryPrefix = "usdRosControlDiffDrive" dictionary libraryTokens = { } } diff --git a/extensions/integrated_controllers/joint_state_broadcaster_controller/README.md b/extensions/integrated_controllers/joint_state_broadcaster_controller/README.md index 7574c4e..cffcde2 100644 --- a/extensions/integrated_controllers/joint_state_broadcaster_controller/README.md +++ b/extensions/integrated_controllers/joint_state_broadcaster_controller/README.md @@ -12,4 +12,4 @@ property of the joint prims and use it for mapping joints in the simulator to th ## Tools ### Schema Definition -The normative OpenUSD schema definition for `RosControlJointStateBroadcasterAPI` is provided in `schema/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. +The normative OpenUSD schema definition for `RosControlJointStateBroadcasterAPI` is provided in `schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. diff --git a/extensions/integrated_controllers/joint_state_broadcaster_controller/schema/schema.usda b/extensions/integrated_controllers/joint_state_broadcaster_controller/schema.usda similarity index 96% rename from extensions/integrated_controllers/joint_state_broadcaster_controller/schema/schema.usda rename to extensions/integrated_controllers/joint_state_broadcaster_controller/schema.usda index 71fc134..24f0af1 100644 --- a/extensions/integrated_controllers/joint_state_broadcaster_controller/schema/schema.usda +++ b/extensions/integrated_controllers/joint_state_broadcaster_controller/schema.usda @@ -12,7 +12,6 @@ over "GLOBAL" ( customData = { string libraryName = "usdRosControlJointStateBroadcaster" string libraryPath = "usdRosControlJointStateBroadcaster" - string libraryPrefix = "usdRosControlJointStateBroadcaster" dictionary libraryTokens = { } } diff --git a/extensions/integrated_controllers/joint_trajectory_controller/README.md b/extensions/integrated_controllers/joint_trajectory_controller/README.md index c3f2467..492aa60 100644 --- a/extensions/integrated_controllers/joint_trajectory_controller/README.md +++ b/extensions/integrated_controllers/joint_trajectory_controller/README.md @@ -17,4 +17,4 @@ use it for mapping trajectory points to joints in the simulator. ## Tools ### Schema Definition -The normative OpenUSD schema definition for `RosControlJointTrajectoryAPI` is provided in `schema/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. +The normative OpenUSD schema definition for `RosControlJointTrajectoryAPI` is provided in `schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. diff --git a/extensions/integrated_controllers/joint_trajectory_controller/schema/schema.usda b/extensions/integrated_controllers/joint_trajectory_controller/schema.usda similarity index 97% rename from extensions/integrated_controllers/joint_trajectory_controller/schema/schema.usda rename to extensions/integrated_controllers/joint_trajectory_controller/schema.usda index 8d9ab7b..58d2162 100644 --- a/extensions/integrated_controllers/joint_trajectory_controller/schema/schema.usda +++ b/extensions/integrated_controllers/joint_trajectory_controller/schema.usda @@ -12,7 +12,6 @@ over "GLOBAL" ( customData = { string libraryName = "usdRosControlJointTrajectory" string libraryPath = "usdRosControlJointTrajectory" - string libraryPrefix = "usdRosControlJointTrajectory" dictionary libraryTokens = { } } diff --git a/extensions/integrated_controllers/rigid_body_controller/README.md b/extensions/integrated_controllers/rigid_body_twist_controller/README.md similarity index 77% rename from extensions/integrated_controllers/rigid_body_controller/README.md rename to extensions/integrated_controllers/rigid_body_twist_controller/README.md index 5f97c30..895aefd 100644 --- a/extensions/integrated_controllers/rigid_body_controller/README.md +++ b/extensions/integrated_controllers/rigid_body_twist_controller/README.md @@ -13,4 +13,4 @@ This provides a general-purpose controller for applying velocity commands to a r ## Tools ### Schema Definition -The normative OpenUSD schema definition for `RosControlRigidBodyTwistAPI` is provided in `schema/schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. +The normative OpenUSD schema definition for `RosControlRigidBodyTwistAPI` is provided in `schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. diff --git a/extensions/integrated_controllers/rigid_body_controller/schema/schema.usda b/extensions/integrated_controllers/rigid_body_twist_controller/schema.usda similarity index 96% rename from extensions/integrated_controllers/rigid_body_controller/schema/schema.usda rename to extensions/integrated_controllers/rigid_body_twist_controller/schema.usda index bf101c4..64f3a18 100644 --- a/extensions/integrated_controllers/rigid_body_controller/schema/schema.usda +++ b/extensions/integrated_controllers/rigid_body_twist_controller/schema.usda @@ -12,7 +12,6 @@ over "GLOBAL" ( customData = { string libraryName = "usdRosControlRigidBodyTwist" string libraryPath = "usdRosControlRigidBodyTwist" - string libraryPrefix = "usdRosControlRigidBodyTwist" dictionary libraryTokens = { } } diff --git a/extensions/integrated_controllers/schema/schema.usda b/extensions/integrated_controllers/schema.usda similarity index 96% rename from extensions/integrated_controllers/schema/schema.usda rename to extensions/integrated_controllers/schema.usda index c926d3b..c1bfb9a 100644 --- a/extensions/integrated_controllers/schema/schema.usda +++ b/extensions/integrated_controllers/schema.usda @@ -12,7 +12,6 @@ over "GLOBAL" ( customData = { string libraryName = "usdRosControl" string libraryPath = "usdRosControl" - string libraryPrefix = "usdRosControl" dictionary libraryTokens = { } } From f135a7820aad3c9c9de731ea40ca480992b73e11 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Wed, 29 Apr 2026 13:04:09 +0200 Subject: [PATCH 098/111] DSet libraryPrefix=Usd on controller schemas MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * this is to maintain per-controller libraries and avoid duplications in generated C++ identifiers (UsdRosControlDiffDriveRosControlDiffDriveAPI). Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- extensions/external_controller/schema.usda | 1 + .../integrated_controllers/diff_drive_controller/schema.usda | 1 + .../joint_state_broadcaster_controller/schema.usda | 1 + .../joint_trajectory_controller/schema.usda | 1 + .../rigid_body_twist_controller/schema.usda | 1 + extensions/integrated_controllers/schema.usda | 1 + 6 files changed, 6 insertions(+) diff --git a/extensions/external_controller/schema.usda b/extensions/external_controller/schema.usda index 07ec297..f342a09 100644 --- a/extensions/external_controller/schema.usda +++ b/extensions/external_controller/schema.usda @@ -12,6 +12,7 @@ over "GLOBAL" ( customData = { string libraryName = "usdRosControlExternal" string libraryPath = "usdRosControlExternal" + string libraryPrefix = "Usd" dictionary libraryTokens = { } } diff --git a/extensions/integrated_controllers/diff_drive_controller/schema.usda b/extensions/integrated_controllers/diff_drive_controller/schema.usda index f123dcd..946363a 100644 --- a/extensions/integrated_controllers/diff_drive_controller/schema.usda +++ b/extensions/integrated_controllers/diff_drive_controller/schema.usda @@ -12,6 +12,7 @@ over "GLOBAL" ( customData = { string libraryName = "usdRosControlDiffDrive" string libraryPath = "usdRosControlDiffDrive" + string libraryPrefix = "Usd" dictionary libraryTokens = { } } diff --git a/extensions/integrated_controllers/joint_state_broadcaster_controller/schema.usda b/extensions/integrated_controllers/joint_state_broadcaster_controller/schema.usda index 24f0af1..7cba36a 100644 --- a/extensions/integrated_controllers/joint_state_broadcaster_controller/schema.usda +++ b/extensions/integrated_controllers/joint_state_broadcaster_controller/schema.usda @@ -12,6 +12,7 @@ over "GLOBAL" ( customData = { string libraryName = "usdRosControlJointStateBroadcaster" string libraryPath = "usdRosControlJointStateBroadcaster" + string libraryPrefix = "Usd" dictionary libraryTokens = { } } diff --git a/extensions/integrated_controllers/joint_trajectory_controller/schema.usda b/extensions/integrated_controllers/joint_trajectory_controller/schema.usda index 58d2162..586da43 100644 --- a/extensions/integrated_controllers/joint_trajectory_controller/schema.usda +++ b/extensions/integrated_controllers/joint_trajectory_controller/schema.usda @@ -12,6 +12,7 @@ over "GLOBAL" ( customData = { string libraryName = "usdRosControlJointTrajectory" string libraryPath = "usdRosControlJointTrajectory" + string libraryPrefix = "Usd" dictionary libraryTokens = { } } diff --git a/extensions/integrated_controllers/rigid_body_twist_controller/schema.usda b/extensions/integrated_controllers/rigid_body_twist_controller/schema.usda index 64f3a18..438a230 100644 --- a/extensions/integrated_controllers/rigid_body_twist_controller/schema.usda +++ b/extensions/integrated_controllers/rigid_body_twist_controller/schema.usda @@ -12,6 +12,7 @@ over "GLOBAL" ( customData = { string libraryName = "usdRosControlRigidBodyTwist" string libraryPath = "usdRosControlRigidBodyTwist" + string libraryPrefix = "Usd" dictionary libraryTokens = { } } diff --git a/extensions/integrated_controllers/schema.usda b/extensions/integrated_controllers/schema.usda index c1bfb9a..60d005b 100644 --- a/extensions/integrated_controllers/schema.usda +++ b/extensions/integrated_controllers/schema.usda @@ -12,6 +12,7 @@ over "GLOBAL" ( customData = { string libraryName = "usdRosControl" string libraryPath = "usdRosControl" + string libraryPrefix = "Usd" dictionary libraryTokens = { } } From cf34a4b4ace422f958bd7b316a0073cdbe39de2f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mateusz=20=C5=BBak?= Date: Wed, 29 Apr 2026 16:09:03 +0200 Subject: [PATCH 099/111] set libraryPath to "." as recommended for non-Pixar plugins MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Mateusz Żak Signed-off-by: Adam Dabrowski --- extensions/external_controller/schema.usda | 2 +- .../integrated_controllers/diff_drive_controller/schema.usda | 2 +- .../joint_state_broadcaster_controller/schema.usda | 2 +- .../joint_trajectory_controller/schema.usda | 2 +- .../rigid_body_twist_controller/schema.usda | 2 +- extensions/integrated_controllers/schema.usda | 2 +- extensions/physics/schema.usda | 2 +- 7 files changed, 7 insertions(+), 7 deletions(-) diff --git a/extensions/external_controller/schema.usda b/extensions/external_controller/schema.usda index f342a09..5f914d6 100644 --- a/extensions/external_controller/schema.usda +++ b/extensions/external_controller/schema.usda @@ -11,7 +11,7 @@ over "GLOBAL" ( customData = { string libraryName = "usdRosControlExternal" - string libraryPath = "usdRosControlExternal" + string libraryPath = "." string libraryPrefix = "Usd" dictionary libraryTokens = { } diff --git a/extensions/integrated_controllers/diff_drive_controller/schema.usda b/extensions/integrated_controllers/diff_drive_controller/schema.usda index 946363a..f5f7fa4 100644 --- a/extensions/integrated_controllers/diff_drive_controller/schema.usda +++ b/extensions/integrated_controllers/diff_drive_controller/schema.usda @@ -11,7 +11,7 @@ over "GLOBAL" ( customData = { string libraryName = "usdRosControlDiffDrive" - string libraryPath = "usdRosControlDiffDrive" + string libraryPath = "." string libraryPrefix = "Usd" dictionary libraryTokens = { } diff --git a/extensions/integrated_controllers/joint_state_broadcaster_controller/schema.usda b/extensions/integrated_controllers/joint_state_broadcaster_controller/schema.usda index 7cba36a..cf78fc6 100644 --- a/extensions/integrated_controllers/joint_state_broadcaster_controller/schema.usda +++ b/extensions/integrated_controllers/joint_state_broadcaster_controller/schema.usda @@ -11,7 +11,7 @@ over "GLOBAL" ( customData = { string libraryName = "usdRosControlJointStateBroadcaster" - string libraryPath = "usdRosControlJointStateBroadcaster" + string libraryPath = "." string libraryPrefix = "Usd" dictionary libraryTokens = { } diff --git a/extensions/integrated_controllers/joint_trajectory_controller/schema.usda b/extensions/integrated_controllers/joint_trajectory_controller/schema.usda index 586da43..484480d 100644 --- a/extensions/integrated_controllers/joint_trajectory_controller/schema.usda +++ b/extensions/integrated_controllers/joint_trajectory_controller/schema.usda @@ -11,7 +11,7 @@ over "GLOBAL" ( customData = { string libraryName = "usdRosControlJointTrajectory" - string libraryPath = "usdRosControlJointTrajectory" + string libraryPath = "." string libraryPrefix = "Usd" dictionary libraryTokens = { } diff --git a/extensions/integrated_controllers/rigid_body_twist_controller/schema.usda b/extensions/integrated_controllers/rigid_body_twist_controller/schema.usda index 438a230..79f0f62 100644 --- a/extensions/integrated_controllers/rigid_body_twist_controller/schema.usda +++ b/extensions/integrated_controllers/rigid_body_twist_controller/schema.usda @@ -11,7 +11,7 @@ over "GLOBAL" ( customData = { string libraryName = "usdRosControlRigidBodyTwist" - string libraryPath = "usdRosControlRigidBodyTwist" + string libraryPath = "." string libraryPrefix = "Usd" dictionary libraryTokens = { } diff --git a/extensions/integrated_controllers/schema.usda b/extensions/integrated_controllers/schema.usda index 60d005b..c1c5766 100644 --- a/extensions/integrated_controllers/schema.usda +++ b/extensions/integrated_controllers/schema.usda @@ -11,7 +11,7 @@ over "GLOBAL" ( customData = { string libraryName = "usdRosControl" - string libraryPath = "usdRosControl" + string libraryPath = "." string libraryPrefix = "Usd" dictionary libraryTokens = { } diff --git a/extensions/physics/schema.usda b/extensions/physics/schema.usda index 4ee9df2..5c2495b 100644 --- a/extensions/physics/schema.usda +++ b/extensions/physics/schema.usda @@ -11,7 +11,7 @@ over "GLOBAL" ( customData = { string libraryName = "usdExtendedPhysics" - string libraryPath = "usdExtendedPhysics" + string libraryPath = "." } ) { From 785d8f71ff9167ccbb7fe29c353ff2823b6b78a7 Mon Sep 17 00:00:00 2001 From: Adam Dabrowski Date: Wed, 29 Apr 2026 13:53:36 +0200 Subject: [PATCH 100/111] REP adherence chapters, minor polish Signed-off-by: Adam Dabrowski --- rep.md | 37 ++++++++++++++++++++++++++++++------- 1 file changed, 30 insertions(+), 7 deletions(-) diff --git a/rep.md b/rep.md index aaeb174..e2dc323 100644 --- a/rep.md +++ b/rep.md @@ -5,8 +5,10 @@ | **REP** | XXXX | | **Title** | OpenUSD Conventions for Simulation Asset Interoperability | | **Authors** | Adam Dabrowski, Mateusz Zak, Michal Pelka (Robotec.ai), Ayush Ghosh, Renato Gasoto (NVIDIA), Franco Cipollone (Ekumen) | +| **PMC Sponsor** | Michael Carroll | +| **PMC** | ROS | | **Status** | Draft | -| **Type** | Standards Track | +| **Category** | Standard | | **Content-Type** | text/markdown | | **Created** | 2026-03-03 | | **Requires** | REP 103, REP 105, OpenUSD Core Spec v1.0.1 | @@ -35,6 +37,8 @@ While OpenUSD adoption is growing quickly, only the core standard specification OpenUSD is championed by the Alliance for OpenUSD (AOUSD) and the ASWF USD Working Group. NVIDIA also plays a key role both as a founding member of AOUSD and in developing OpenUSD for robotics through Omniverse, Isaac Sim and Newton. This REP builds on top of significant work done by all these entities, extending it by addressing what is not yet standardized but urgently needed for OpenUSD interoperability in the ROS simulation ecosystem, and standardizing against practices that result in a vendor lock-in. As such, this REP is designed to adapt upstream standards for the ROS community, while serving as a reference to influence future decisions by AOUSD and ASWF. +The motivation is not to replace any of existing formats, but to regulate a widely adopted, powerful standard so that it serves the ROS community, strengthening ROS role in the development of Physical AI. + ## Specification The keywords "must", "must not", "required", "shall", "shall not", "should", "should not", "recommended", "may", and "optional" in this document are to be interpreted as described in RFC 2119. @@ -367,7 +371,7 @@ The normative OpenUSD schema definition for all `Ros*API` schemas is provided in Due to the number and dynamic nature of extensions for physics, controls and sensors, they will be handled as extension schemas to interoperability profile compliance. Extension schemas will be submitted and ratified independently. The following is mandated: -- A submission must follow the rules of this REP where applicable, e.g. including declarative parameters that can be implemented accross simulators, and adhering to general rules for sensors and control schemas (e.g. graceful degradation). A submission may include one or more vendor or physic engine specific layers as outlined in Section 1.4. +- A submission must follow the rules of this REP where applicable, e.g. including declarative parameters that can be implemented across simulators, and adhering to general rules for sensors and control schemas (e.g. graceful degradation). A submission may include one or more vendor or physic engine specific layers as outlined in Section 1.4. - A submission must include addition to Compliance Checker and any other supplementary conversion tools within the repository, which allows the use of new schema to be validated. A submission must also include documentation of use and a minimal example asset. #### 4.2.1 General Extension Schema Rules @@ -382,7 +386,7 @@ Additional schemas are to be defined through extensions, chiefly for sensors and To leverage emerging simulation features without violating vendor-neutrality (Section 1.4), the registry will host physics extension schemas based on upstream proposals (e.g., from Linux Foundation Newton USD Schemas[NEWTON-SCHEMAS] or AOUSD working groups), as "Incubating Schemas". These schemas must adhere to the following rules: -* **Namespace:** To prevent collisions with core OpenUSD updates, incubating physics schemas must use the `ExtendedPhysics` class prefix and the `ext_physics:` property prefix. Vendor prefixes (e.g., `newton:`) and core prefixes (e.g., `physics:`) are prohibited. +* **Namespace:** To prevent collisions with core OpenUSD updates, incubating physics schemas must use the `ExtendedPhysics` class prefix and the `ext_physics:` property prefix, followed by a concept-specific sub-namespace (e.g. `ext_physics::mimic`). Vendor prefixes (e.g., `newton:`) and core prefixes (e.g., `physics:`) are prohibited. * **Translation:** OpenUSD does not natively support schema aliasing. Assets generated by tools using vendor-specific staging schemas must be processed via ecosystem tooling (e.g., automated compliance fixers) to replace them with their `ExtendedPhysics*` equivalents prior to distribution. @@ -405,9 +409,9 @@ In addition to general extension schema rules, sensor schemas must follow these A canonical repository of open-source, compliant simulation assets is to be established as `ros-simulation/openusd-assets`. These assets will have payloads hosted independently (e.g. in a dedicated repository such as Hugging Face) and must pass the Compliance Checker. -## Tools +## Implementation -The following tools will be provided within `ros-simulation/openusd-schemas` repository alongside core and extension schemas: +This REP is implemented through the core schema and the registry described in Section 4, as well as tools to be provided within `ros-simulation/openusd-schemas` repository: ### Compliance Checker A REP-XXXX compliance checker is to be developed and shared with the community. The tool will provide validation of all REP recommendations for OpenUSD assets and supply actionable feedback for the user for every violation or non-conformance. @@ -420,6 +424,24 @@ A compliance fixer (e.g., `rep_sanitizer`) will be provided for common issues th * **Transform Standardization:** Automatically decomposing baked 4x4 CAD matrices (`xformOp:transform`) into the mandated `translate` and `orient` operations (Section 1.1). * **Vendor Isolation:** Scanning for and extracting engine-specific properties (e.g., `isaac:`, `mujoco:`) from the baseline payload into isolated proprietary overlays (Section 1.4). +## Rationale + +- **Why OpenUSD?** This REP does not argue against any other formats. OpenUSD is useful for robotics due to: + - Volume and quality of assets authored and a value such assets have for building robotic simulations. + - Adoption and existing drive for the standard towards robotics. + - Connection to a broad ecosystem and tooling. +- **Extensions** A version of this REP with sensor and control schemas was considered, but the scale of dealing with all of these at once speaks against such an approach. Thus, the REP takes on a core + extensions model, following OpenUSD and glTF 2.0 practice. +- **Scope limit** This REP does not regulate how simulation-level interfaces (such as `/clock` topic) are to be implemented, only that they are not a part of compliant assets. This scope limit is important so that diverse implementations of ROS communication in simulators can be supported. +- **glTF** glTF 2.0 was selected as primary export pathway due to support in multiple ROS simulators, its complementary lightweight nature, and an ongoing development of the format in direction of robotics simulation. + +## How to Teach This + +The standard introduced by this REP is a subject of automation through compliance, assistant and conversion tooling. It is to be used by simulation asset authors (including use of new schemas), developers of simulation import and export features, and developers of compliance and conversion tooling. However, resulting compliant assets are beneficial for a broad robotics community. + +### Documentation Updates + +- **ROS Tutorials->Simulators:** add a new chapter on interoperable assets and cross-reference the compliant asset repository. + ## References * **[NVIDIA-ETL-PIPELINE]** NVIDIA, Intrinsic, Disney Research. "Using OpenUSD for Modular and Scalable Robotic Simulation and Development". URL: `https://developer.nvidia.com/blog/using-openusd-for-modular-and-scalable-robotic-simulation-and-development/` @@ -431,6 +453,7 @@ A compliance fixer (e.g., `rep_sanitizer`) will be provided for common issues th * **[GLTF-EXT-INSTANCING]** Khronos Group, "EXT_mesh_gpu_instancing Extension Specification". * **[NEWTON-SCHEMAS]** Linux Foundation Newton Project. "Newton USD Schemas". URL: `https://github.com/newton-physics/newton-usd-schemas` -## Copyright -This document will be placed in the public domain upon being submitted as PR to a REP proposal by original authors. This text will be changed to "This document is placed in the public domain". +## License +This document is marked CC0 1.0 Universal. +To view a copy of this mark, visit [https://creativecommons.org/publicdomain/zero/1.0/](https://creativecommons.org/publicdomain/zero/1.0/). From fef677dee1b8e9a350fb82432f09b7242689fa93 Mon Sep 17 00:00:00 2001 From: Adam Dabrowski Date: Wed, 29 Apr 2026 16:00:03 +0200 Subject: [PATCH 101/111] Template conformance Co-authored-by Mateusz Zak Signed-off-by: Adam Dabrowski --- rep.md | 60 +++++++++++++++++++++++++++++----------------------------- 1 file changed, 30 insertions(+), 30 deletions(-) diff --git a/rep.md b/rep.md index e2dc323..82198d7 100644 --- a/rep.md +++ b/rep.md @@ -1,17 +1,18 @@ -# REP XXXX -- OpenUSD Conventions for Simulation Asset Interoperability - -| Field | Value | -| :--- | :--- | -| **REP** | XXXX | -| **Title** | OpenUSD Conventions for Simulation Asset Interoperability | -| **Authors** | Adam Dabrowski, Mateusz Zak, Michal Pelka (Robotec.ai), Ayush Ghosh, Renato Gasoto (NVIDIA), Franco Cipollone (Ekumen) | -| **PMC Sponsor** | Michael Carroll | -| **PMC** | ROS | -| **Status** | Draft | -| **Category** | Standard | -| **Content-Type** | text/markdown | -| **Created** | 2026-03-03 | -| **Requires** | REP 103, REP 105, OpenUSD Core Spec v1.0.1 | + +--- +layout: post +REP: 0158:2026 +title: OpenUSD Conventions for Simulation Asset Interoperability +authors: Adam Dabrowski, Mateusz Zak, Michal Pelka (Robotec.ai), Ayush Ghosh, Renato Gasoto (NVIDIA), Franco Cipollone (Ekumen) +PMC Sponsor: Michael Carroll +PMCs: ROS +discussion: Pending +tag: Draft +category: Standard +date: 2026-03-03 +requires: REP 103, REP 105 +pin: true +--- ## Abstract @@ -408,22 +409,6 @@ In addition to general extension schema rules, sensor schemas must follow these A canonical repository of open-source, compliant simulation assets is to be established as `ros-simulation/openusd-assets`. These assets will have payloads hosted independently (e.g. in a dedicated repository such as Hugging Face) and must pass the Compliance Checker. - -## Implementation - -This REP is implemented through the core schema and the registry described in Section 4, as well as tools to be provided within `ros-simulation/openusd-schemas` repository: - -### Compliance Checker -A REP-XXXX compliance checker is to be developed and shared with the community. The tool will provide validation of all REP recommendations for OpenUSD assets and supply actionable feedback for the user for every violation or non-conformance. - -### Supplementary migration tools - -A compliance fixer (e.g., `rep_sanitizer`) will be provided for common issues that can be handled by automated scripting, including: - -* **Schema Translation:** Stripping proprietary staging schemas and replacing them with their neutral `ExtendedPhysics` equivalents (see Section 4.2.2). -* **Transform Standardization:** Automatically decomposing baked 4x4 CAD matrices (`xformOp:transform`) into the mandated `translate` and `orient` operations (Section 1.1). -* **Vendor Isolation:** Scanning for and extracting engine-specific properties (e.g., `isaac:`, `mujoco:`) from the baseline payload into isolated proprietary overlays (Section 1.4). - ## Rationale - **Why OpenUSD?** This REP does not argue against any other formats. OpenUSD is useful for robotics due to: @@ -442,6 +427,21 @@ The standard introduced by this REP is a subject of automation through complianc - **ROS Tutorials->Simulators:** add a new chapter on interoperable assets and cross-reference the compliant asset repository. +## Implementation + +This REP is implemented through the core schema and the registry described in Section 4, as well as tools to be provided within `ros-simulation/openusd-schemas` repository: + +### Compliance Checker +A REP compliance checker is to be developed and shared with the community. The tool will provide validation of all REP recommendations for OpenUSD assets and supply actionable feedback for the user for every violation or non-conformance. + +### Supplementary migration tools + +A compliance fixer (e.g., `rep_sanitizer`) will be provided for common issues that can be handled by automated scripting, including: + +* **Schema Translation:** Stripping proprietary staging schemas and replacing them with their neutral `ExtendedPhysics` equivalents (see Section 4.2.2). +* **Transform Standardization:** Automatically decomposing baked 4x4 CAD matrices (`xformOp:transform`) into the mandated `translate` and `orient` operations (Section 1.1). +* **Vendor Isolation:** Scanning for and extracting engine-specific properties (e.g., `isaac:`, `mujoco:`) from the baseline payload into isolated proprietary overlays (Section 1.4). + ## References * **[NVIDIA-ETL-PIPELINE]** NVIDIA, Intrinsic, Disney Research. "Using OpenUSD for Modular and Scalable Robotic Simulation and Development". URL: `https://developer.nvidia.com/blog/using-openusd-for-modular-and-scalable-robotic-simulation-and-development/` From 2209bb2e33c2cb92614b33d1b854754a3cfca6b3 Mon Sep 17 00:00:00 2001 From: Adam Dabrowski Date: Wed, 29 Apr 2026 16:22:50 +0200 Subject: [PATCH 102/111] fix Signed-off-by: Adam Dabrowski --- rep.md | 1 - 1 file changed, 1 deletion(-) diff --git a/rep.md b/rep.md index 82198d7..190195d 100644 --- a/rep.md +++ b/rep.md @@ -1,4 +1,3 @@ - --- layout: post REP: 0158:2026 From e116e7abf9cddc954ebfa13a90e9394a59d2d3b5 Mon Sep 17 00:00:00 2001 From: Adam Dabrowski Date: Wed, 29 Apr 2026 16:24:15 +0200 Subject: [PATCH 103/111] : Signed-off-by: Adam Dabrowski --- rep.md | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/rep.md b/rep.md index 190195d..9b4573e 100644 --- a/rep.md +++ b/rep.md @@ -410,13 +410,13 @@ A canonical repository of open-source, compliant simulation assets is to be esta ## Rationale -- **Why OpenUSD?** This REP does not argue against any other formats. OpenUSD is useful for robotics due to: +- **Why OpenUSD?:** This REP does not argue against any other formats. OpenUSD is useful for robotics due to: - Volume and quality of assets authored and a value such assets have for building robotic simulations. - Adoption and existing drive for the standard towards robotics. - Connection to a broad ecosystem and tooling. -- **Extensions** A version of this REP with sensor and control schemas was considered, but the scale of dealing with all of these at once speaks against such an approach. Thus, the REP takes on a core + extensions model, following OpenUSD and glTF 2.0 practice. -- **Scope limit** This REP does not regulate how simulation-level interfaces (such as `/clock` topic) are to be implemented, only that they are not a part of compliant assets. This scope limit is important so that diverse implementations of ROS communication in simulators can be supported. -- **glTF** glTF 2.0 was selected as primary export pathway due to support in multiple ROS simulators, its complementary lightweight nature, and an ongoing development of the format in direction of robotics simulation. +- **Extensions:** A version of this REP with sensor and control schemas was considered, but the scale of dealing with all of these at once speaks against such an approach. Thus, the REP takes on a core + extensions model, following OpenUSD and glTF 2.0 practice. +- **Scope limit:** This REP does not regulate how simulation-level interfaces (such as `/clock` topic) are to be implemented, only that they are not a part of compliant assets. This scope limit is important so that diverse implementations of ROS communication in simulators can be supported. +- **glTF:** glTF 2.0 was selected as primary export pathway due to support in multiple ROS simulators, its complementary lightweight nature, and an ongoing development of the format in direction of robotics simulation. ## How to Teach This From 3ba487d9030efdc8d3fc608060d623978ee8b6a5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Thu, 30 Apr 2026 10:40:55 +0200 Subject: [PATCH 104/111] Update rep.md Wording polish and update of the chapter number Signed-off-by: Adam Dabrowski --- rep.md | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/rep.md b/rep.md index 9b4573e..5fef565 100644 --- a/rep.md +++ b/rep.md @@ -117,7 +117,7 @@ OpenUSD `VariantSets` are the normative mechanism for asset reusability (e.g., e * *Note: This REP aligns with the domain convention requested in the active AOUSD proposal: [Separation of Concerns for Identifiers in USD (PR #105)](https://github.com/PixarAnimationStudios/OpenUSD-proposals/pull/105) Once AOUSD ratifies a standardized mechanism for external identifiers, this REP will adopt it.* * **Path Resolution:** Internal references must use relative paths (`./geo/mesh.usdc`). For distributed, highly interoperable assets, all file dependencies should be self-contained and rely exclusively on relative paths. * **ROS packages:** External dependencies targeting other ROS packages must use the package:// URI scheme. Absolute paths or proprietary schemes (e.g., omniverse://) are prohibited for external package references. Tooling and simulators aiming for ROS interoperability must provide a custom OpenUSD ArResolver plugin to resolve these URIs. -* **Native Composition vs. Custom Prefabs:** The use of custom or vendor-specific string attributes (e.g., `custom string my_sim:prefabPath = "robot.usd"`) to dynamically load, instantiate, or compose assets at runtime is strictly prohibited for interoperable assets. Asset composition must rely purely on native OpenUSD references or payloads. +* **Native Composition vs. Custom Prefabs:** Assets must not use custom or vendor-specific string attributes (e.g., `custom string my_sim:prefabPath = "robot.usd"`) to dynamically load, instantiate, or compose assets at runtime. Asset composition must rely purely on native OpenUSD references or payloads. * **FileFormat Plugins:** OpenUSD supports FileFormat plugins (e.g.,`usdMjcf`) to dynamically translate legacy formats into USD stages at runtime. While these plugins are recommended for import pathways, this REP governs the *resulting in-memory OpenUSD data*. Plugins interfacing with the ROS ecosystem must generate stages that conform to the physical hierarchies and API schemas defined in this document. #### 1.2.6 Parallel Simulation and Instancing @@ -136,7 +136,7 @@ OpenUSD's native instancing mechanisms are designed for repetitive visual and st * *Static Environments:* Fixed props (e.g., walls, racks) must possess a PhysicsCollisionAPI but omit the PhysicsRigidBodyAPI. OpenUSD implicitly treats these as having zero velocity and infinite mass. * *Robot Anchors:* A fixed robot base must have a valid mass > 0 and be anchored via a UsdPhysicsFixedJoint with an empty physics:body0 relationship (which natively represents the world). * *Kinematic Bodies:* Moving bodies that are animated but not dynamically driven by physics should set the physics:kinematicEnabled attribute to true. - * *Dummy Frames:* Non-physical dummy frames (e.g., `camera_optical_frame`) must not possess a `PhysicsRigidBodyAPI`. They should be tracked using the `RosFrameAPI` as defined in Section 2.8. + * *Dummy Frames:* Non-physical dummy frames (e.g., `camera_optical_frame`) must not possess a `PhysicsRigidBodyAPI`. They should be tracked using the `RosFrameAPI` as defined in Section 2.7. * **Inertia Representation:** Unlike URDF and SDFormat's 6-value symmetric matrix, OpenUSD requires an eigendecomposed inertia tensor. Converters must mathematically decompose the source matrix into physics:diagonalInertia (eigenvalues) and physics:principalAxes (quaternion). This native decomposed form is the strict single source of truth; custom 6-value array attributes must not be authored or parsed. * **Extended Physics:** Many physics features are missing in `UsdPhysics`, including mimic joints, deformable bodies and advanced friction. Authors must use `ExtendedPhysics*` schemas for interoperability, following Section 4.2.2. When interoperable schema is not available, assets must isolate specific feature, e.g. deformable soft-body physics into a feature layer for specific domain or vendor (see Section 1.2.1). @@ -167,8 +167,8 @@ To ensure deterministic contact dynamics across engines, authors must bind a `Us To guarantee interoperability across different solvers, physical properties and engine-specific parameters must be explicitly decoupled into separate functional layers: -* **Neutral Physics (`physics.usda`):** A universally shared layer containing exclusively core `UsdPhysics` schemas (rigid bodies, joints, limits, mass properties). This file must strictly adhere to the standard OpenUSD Physics specification and must not contain any vendor-specific extensions. -* **Engine Tuning (`physx.usda`, `mujoco.usda`, `isaac.usda`):** Engine-specific parameters (e.g., proprietary solver iterations, specialized friction models, GPU tensors) not covered by core OpenUSD schemas must be explicitly namespaced with a vendor prefix (e.g., `mujoco:`, `isaac:`). These must be strictly isolated within discrete "Proprietary Layers" (Section 1.2.1) and never authored in the baseline simulation payload or neutral physics layer. Authors must strive to minimize this proprietary layer to what is strictly necessary. +* **Neutral Physics (`physics.usda`):** A universally shared layer containing exclusively core `UsdPhysics` schemas (rigid bodies, joints, limits, mass properties). This file must adhere to the standard OpenUSD Physics specification and must not contain any vendor-specific extensions. +* **Engine Tuning (`physx.usda`, `mujoco.usda`, `isaac.usda`):** Engine-specific parameters (e.g., proprietary solver iterations, specialized friction models, GPU tensors) not covered by core OpenUSD schemas must be explicitly namespaced with a vendor prefix (e.g., `mujoco:`, `isaac:`). These must be isolated within discrete "Proprietary Layers" (Section 1.2.1) and never authored in the baseline simulation payload or neutral physics layer. Authors must strive to minimize this proprietary layer to what is strictly necessary. --- @@ -237,7 +237,7 @@ ROS interface schemas (`RosTopicAPI`, `RosServiceAPI`, `RosActionAPI`) must be a ### 2.3 Interface Resolution For all schema types (Topics, Services, Actions) defined below: * **Type Resolution:** Tooling and compliant simulators must attempt to resolve the `ros:*:type` string (e.g., `sensor_msgs/msg/Image`) dynamically against the sourced ROS environment. If the interface type is not found, the simulator must safely disable that specific interface, allow the rest of the asset to function normally, and emit a distinct warning/error. -* **Name Validation:** All `ros:*:name` values must strictly adhere to ROS topic naming rules (alphanumeric, underscores, and forward slashes only; cannot start with a number). +* **Name Validation:** All `ros:*:name` values must adhere to ROS topic naming rules (alphanumeric, underscores, and forward slashes only; cannot start with a number). * **Initialization State:** All ROS interfaces (`RosTopicAPI`, `RosServiceAPI`, `RosActionAPI`) support a `bool ros:*:starts_enabled` attribute (`Optional`, `Default: true`). This dictates the initialization state of the interface at load time, preventing startup conflicts or unwanted compute overhead. Runtime lifecycle management (e.g., dynamically disabling the publisher mid-simulation) is the responsibility of the simulator. ### 2.4 Topic Interface (`RosTopicAPI`) @@ -309,12 +309,12 @@ If this property is missing, simulators must fall back to using the prim name. ## 3. Export and Conversion -OpenUSD is a vast standard supporting complex features. To guarantee that assets can be converted to glTF 2.0 and successfully exported to work with lightweight applications and standard ROS tools (e.g., RViz, MoveIt), such as for publishing of a URDF string to `/robot_description`, without mandating native OpenUSD support, assets must adhere to this constrained subset. +To guarantee that assets can be converted to glTF 2.0 and successfully exported to work with lightweight applications and standard ROS tools (e.g., RViz, MoveIt), such as for publishing of a URDF string to `/robot_description`, without mandating native OpenUSD support, assets must adhere to this constrained subset. ### 3.1 Material Portability * **Normative Surface:** Assets must use UsdPreviewSurface as the normative surface definition to ensure a direct mapping to glTF 2.0's pbrMetallicRoughness workflow. Target converters may also support OpenPBR[AOUSD-OPENPBR]. * **Material Terminals (Render Contexts)**: A UsdShadeMaterial acts as a container. Proprietary shaders (e.g., MDL, OSL) must not replace the universal surface output. Assets should bind a single Material universally. Inside that Material, the UsdPreviewSurface must be wired to the universal outputs:surface terminal (which glTF/web converters natively parse), while proprietary shaders may be included by wiring them to renderer-specific terminals (e.g., outputs:mdl:surface). -* **Texture Coordinates & UDIMs:** Multi-tile UV mapping (UDIMs) is unsupported by glTF 2.0 and many real-time engines, and must not be used. Unique UVs must be packed strictly into the [0, 1] space (Texture Atlasing). If multiple high-resolution textures are required for a single mesh, authors must partition the geometry using UsdGeomSubset (with `familyName="materialBind"`) and assign separate materials. UV coordinates outside [0, 1] are strictly reserved for seamless tiling textures using repeat wrap modes. +* **Texture Coordinates & UDIMs:** Multi-tile UV mapping (UDIMs) is unsupported by glTF 2.0 and many real-time engines, and must not be used. Unique UVs must be packed into the [0, 1] space (Texture Atlasing). If multiple high-resolution textures are required for a single mesh, authors must partition the geometry using UsdGeomSubset (with `familyName="materialBind"`) and assign separate materials. UV coordinates outside [0, 1] are reserved for seamless tiling textures using repeat wrap modes. ### 3.2 Texture File Formats To ensure native portability across OpenUSD, lightweight simulators, and glTF 2.0, texture formats are constrained: @@ -333,7 +333,7 @@ Procedural texture graphs (noise generation, math nodes, node graphs) are not in ### 3.4 Geometry Constraints * **Triangulation:** Collision meshes must be explicitly triangulated by the author. Visual meshes may use quads or n-gons, but converters targeting glTF 2.0 must triangulate all geometry at export time. * **Face Orientation:** Meshes must use `orientation = "rightHanded"` (the OpenUSD default), which defines counter-clockwise vertex winding as front-facing. This aligns with glTF 2.0's mandatory CCW front faces. Assets must not rely on `doubleSided = true` to mask incorrect winding. -* **Manifold topology:** Collision meshes must be watertight (closed, manifold) and free of self-intersections to ensure stable physics and mass derivation. Non-manifold geometry (e.g., open edges) is strictly limited to purely visual meshes. +* **Manifold topology:** Collision meshes must be watertight (closed, manifold) and free of self-intersections to ensure stable physics and mass derivation. Non-manifold geometry (e.g., open edges) is limited to purely visual meshes. ### 3.5 Instanceable Leaves Repetitive geometry (bolts, LED arrays on a sensor) must utilize native OpenUSD instancing to minimize memory footprint. Authors must only instance leaf geometry (visuals and colliders), not logical Prims containing PhysicsRigidBodyAPI, Joints, or Ros*API schemas, as OpenUSD instance proxies obscure child prims from relationship targeting. Authors must use one of two mechanisms to ensure correct glTF conversion: @@ -394,7 +394,7 @@ To leverage emerging simulation features without violating vendor-neutrality (Se In addition to general extension schema rules, control interfaces and controllers must follow these rules: * **Explicit Targeting:** Controllers should be decoupled from the physical rigid-body hierarchy: authors should place them on dedicated logical prims (e.g., `/Robot/Controllers`) and explicitly target their actuated mechanisms. Simulators must not rely on Xform scene graph nesting to infer a controller's scope. Controllers must declare targets using OpenUSD relationships (`rel`) or standard `UsdCollectionAPI` collections. -* **Actuation via Physics:** Control schemas should interface with dynamic bodies strictly through the simulation's physics pipeline. Position, velocity, and effort targets must be routed through normative OpenUSD dynamics paradigms (e.g., `UsdPhysicsDriveAPI`) or universally ratified extension schemas, deferring to isolated vendor extensions only when a ratified standard for the required actuation modality does not exist. Controllers that directly manipulate spatial transforms should only actuate prims where `physics:kinematicEnabled = true`. Control schemas should not handle simulator-level state changes (e.g., native simulator state APIs or ROS `simulation_interfaces`), including resets for RL training or entity state manipulation. +* **Actuation via Physics:** Control schemas should interface with dynamic bodies through the simulation's physics pipeline. Position, velocity, and effort targets must be routed through normative OpenUSD dynamics paradigms (e.g., `UsdPhysicsDriveAPI`) or universally ratified extension schemas, deferring to isolated vendor extensions only when a ratified standard for the required actuation modality does not exist. Controllers that directly manipulate spatial transforms should only actuate prims where `physics:kinematicEnabled = true`. Control schemas should not handle simulator-level state changes (e.g., native simulator state APIs or ROS `simulation_interfaces`), including resets for RL training or entity state manipulation. * **Runtime selection:** A single asset may contain multiple, mutually exclusive control paradigms for the same hardware (e.g., trajectory control vs. direct effort control). While `VariantSets` remain the standard for structural hardware changes, simulators should provide dynamic lifecycle management of controllers to support runtime switching. The asset's authored state must prevent write conflicts at load time by ensuring controllers actuating the same targets are not simultaneously active (e.g., via a `bool control:starts_enabled` schema property). #### 4.2.4 Sensor Schemas From bc64cd219f0ef179e13aea7a86fd60ddcb9025af Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Adam=20D=C4=85browski?= Date: Thu, 30 Apr 2026 12:41:57 +0200 Subject: [PATCH 105/111] Update rep.md Assorted improvements Signed-off-by: Adam Dabrowski --- rep.md | 19 ++++++++++++------- 1 file changed, 12 insertions(+), 7 deletions(-) diff --git a/rep.md b/rep.md index 5fef565..3a8924d 100644 --- a/rep.md +++ b/rep.md @@ -29,11 +29,11 @@ To achieve this, the specification addresses four key areas: Following the OpenUSD and glTF 2.0 model, this REP establishes a Core Standard, and proposes general rules for handling of extension schemas, including for control interfaces and sensor simulation. -## Motivation +## Motivation The ROS ecosystem chiefly relies on URDF and SDF for describing robots and environments. These formats are almost entirely confined to the ROS and Gazebo ecosystems. OpenUSD has emerged as an industry standard supported by a multitude of tools and allows artists to collaborate with simulation engineers without problematic conversions between a variety of 3D and XML formats. Ensuring OpenUSD works well with ROS integrations across robotics simulators will increase ecosystem interoperability and strengthen ROS's position in physical AI workflows such as synthetic data and generative pipelines. OpenUSD is a powerful format with an extensible architecture allowing it to capture all the semantics of other popular formats. -While OpenUSD adoption is growing quickly, only the core standard specification has been ratified so far, leaving most of what's interesting for robotics uncovered. OpenUSD lacks standardized semantic representations for ROS interfaces and standard rules for mapping to ROS concepts such as frames and TF trees. OpenUSD's flexibility also permits practices that degrade interoperability, such as proprietary extensions, defining execution instead of intent, and overfitting to particular workflows. +While OpenUSD adoption is growing quickly, only the core standard specification has been ratified so far, leaving many key features for robotics uncovered. OpenUSD lacks standardized semantic representations for ROS interfaces and standard rules for mapping to ROS concepts such as frames and TF trees. OpenUSD's flexibility also permits practices that degrade interoperability, such as proprietary extensions, defining execution instead of intent, and overfitting to particular workflows. OpenUSD is championed by the Alliance for OpenUSD (AOUSD) and the ASWF USD Working Group. NVIDIA also plays a key role both as a founding member of AOUSD and in developing OpenUSD for robotics through Omniverse, Isaac Sim and Newton. This REP builds on top of significant work done by all these entities, extending it by addressing what is not yet standardized but urgently needed for OpenUSD interoperability in the ROS simulation ecosystem, and standardizing against practices that result in a vendor lock-in. As such, this REP is designed to adapt upstream standards for the ROS community, while serving as a reference to influence future decisions by AOUSD and ASWF. @@ -138,7 +138,7 @@ OpenUSD's native instancing mechanisms are designed for repetitive visual and st * *Kinematic Bodies:* Moving bodies that are animated but not dynamically driven by physics should set the physics:kinematicEnabled attribute to true. * *Dummy Frames:* Non-physical dummy frames (e.g., `camera_optical_frame`) must not possess a `PhysicsRigidBodyAPI`. They should be tracked using the `RosFrameAPI` as defined in Section 2.7. * **Inertia Representation:** Unlike URDF and SDFormat's 6-value symmetric matrix, OpenUSD requires an eigendecomposed inertia tensor. Converters must mathematically decompose the source matrix into physics:diagonalInertia (eigenvalues) and physics:principalAxes (quaternion). This native decomposed form is the strict single source of truth; custom 6-value array attributes must not be authored or parsed. -* **Extended Physics:** Many physics features are missing in `UsdPhysics`, including mimic joints, deformable bodies and advanced friction. Authors must use `ExtendedPhysics*` schemas for interoperability, following Section 4.2.2. When interoperable schema is not available, assets must isolate specific feature, e.g. deformable soft-body physics into a feature layer for specific domain or vendor (see Section 1.2.1). +* **Extended Physics:** Many physics features are missing in `UsdPhysics`, including mimic joints, deformable bodies and advanced friction. Authors must use `ExtendedPhysics*` schemas for interoperability, following Section 4.2.2. When interoperable schema is not available, assets must isolate the specific feature, e.g. deformable soft-body physics into a feature layer for specific domain or vendor (see Section 1.2.1). #### 1.3.1 Collisions @@ -300,12 +300,10 @@ Simulator-level interfaces are prohibited in assets to avoid clashes, including: * `/clock` topic (`rosgraph_msgs/msg/Clock` interface) for simulation time. * Any interfaces included in the `simulation_interfaces` package (e.g. spawning, simulation control). -### 2.10 Custom names to ROS joints. +### 2.10 Custom ROS joint names. A number of concepts in ROS (e.g. robot descriptions, controllers) rely 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 ``). -If this property is missing, simulators must fall back to using the prim name. +To ensure that joints are correctly identified and mapped to said concepts, the custom property `ros:joint:name` may be applied to all Prims bearing built-in `UsdPhysicsJoint` schema. If this property is authored, its value is the single source of truth for ROS-facing joint identity, including mapping for `FollowJointTrajectory` action goals, `JointState` messages, integration with `ros2_control`, and for conversion to other formats (e.g., MJCF's ``). Authors should keep the property value and the prim name aligned where naming rules permit. If this property is missing, simulators must fall back to using the prim name. ## 3. Export and Conversion @@ -389,6 +387,7 @@ To leverage emerging simulation features without violating vendor-neutrality (Se * **Namespace:** To prevent collisions with core OpenUSD updates, incubating physics schemas must use the `ExtendedPhysics` class prefix and the `ext_physics:` property prefix, followed by a concept-specific sub-namespace (e.g. `ext_physics::mimic`). Vendor prefixes (e.g., `newton:`) and core prefixes (e.g., `physics:`) are prohibited. * **Translation:** OpenUSD does not natively support schema aliasing. Assets generated by tools using vendor-specific staging schemas must be processed via ecosystem tooling (e.g., automated compliance fixers) to replace them with their `ExtendedPhysics*` equivalents prior to distribution. +**Schema Lifecycle:** Physics extensions progress through three namespaces: vendor prefixes (e.g., `newton:`) during in-tool development, the neutral `ext_physics:` prefix for cross-engine incubation in the schema registry, and `physics:` once AOUSD ratifies the schema into core OpenUSD. The `rep_sanitizer` tool handles the first transition; the deprecation policy in Section 4.2.1 handles the second. Vendor prefixes are prohibited in distributed assets because they encode engine identity into properties that should be engine-neutral; the `physics:` prefix is reserved for AOUSD-ratified schemas. `ext_physics:` exists to fill the gap between the two. #### 4.2.3 Control Schemas @@ -417,6 +416,7 @@ A canonical repository of open-source, compliant simulation assets is to be esta - **Extensions:** A version of this REP with sensor and control schemas was considered, but the scale of dealing with all of these at once speaks against such an approach. Thus, the REP takes on a core + extensions model, following OpenUSD and glTF 2.0 practice. - **Scope limit:** This REP does not regulate how simulation-level interfaces (such as `/clock` topic) are to be implemented, only that they are not a part of compliant assets. This scope limit is important so that diverse implementations of ROS communication in simulators can be supported. - **glTF:** glTF 2.0 was selected as primary export pathway due to support in multiple ROS simulators, its complementary lightweight nature, and an ongoing development of the format in direction of robotics simulation. +- **Upstream dependency:** This REP intentionally tracks active work at AOUSD, including the Separation of Concerns proposal for asset identifiers (Section 1.2.5), incubating physics schemas (Section 4.2.2), and forthcoming output from the physics and robotics Working Groups. As these are ratified, this REP will adopt the official mechanisms and deprecate its provisional equivalents. This imposes a maintenance burden on REP and schema-registry maintainers and a migration burden on simulator vendors and asset authors, but is the correct trade-off: the alternative is a ROS-specific dialect of OpenUSD that forfeits the ecosystem advantages motivating its adoption in the first place. ## How to Teach This @@ -426,6 +426,11 @@ The standard introduced by this REP is a subject of automation through complianc - **ROS Tutorials->Simulators:** add a new chapter on interoperable assets and cross-reference the compliant asset repository. +### Other Resources + +- **Reference assets:** the canonical asset repository (Section 4.3) serves as worked examples; each asset is documented with the layer structure, applied schemas and compliance notes, making it easy to replicate. +- **Compliance checker:** the compliance checker will output exact violations with references to the corresponding REP sections, making it easy to adjust assets step-by-step and learn the standard in the process. + ## Implementation This REP is implemented through the core schema and the registry described in Section 4, as well as tools to be provided within `ros-simulation/openusd-schemas` repository: From 0fd6f42215a4ae95151e8c7c205a078e3c02a8ff Mon Sep 17 00:00:00 2001 From: Adam Dabrowski Date: Thu, 30 Apr 2026 12:52:46 +0200 Subject: [PATCH 106/111] adjusted 3.7 for clarity Signed-off-by: Adam Dabrowski --- rep.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/rep.md b/rep.md index 3a8924d..6f177e4 100644 --- a/rep.md +++ b/rep.md @@ -346,9 +346,9 @@ Lighting must be authored using core UsdLux schemas. To ensure deterministic ill ### 3.7 Variant Baking for Export While OpenUSD natively handles structural variants, many of the simulation tools and formats in the ecosystem don't, including URDF, SDF and glTF 2.0. Due to the burden of implementation, this REP proposes both a baseline and an advanced compliance: -* **Baseline compliance:** Converters must export only the active or default variant, destructively discarding all others. This resolved state must be baked by flattening OpenUSD composition arcs into a static, logically nested kinematic tree. Never flatten into world-space, as this permanently destroys local joint transforms and ROS TF trees. +* **Baseline compliance:** Converters must export only the resolved variant: an explicit selection if provided, otherwise the default authored per Section 1.2.4, destructively discarding all others. This resolved state must be baked by flattening OpenUSD composition arcs into a static, logically nested kinematic tree. Never flatten into world-space, as this permanently destroys local joint transforms and ROS TF trees. * **Advanced compliance (material variants support):** Capable exporters may preserve material variations via the `KHR_materials_variants` extension. Because OpenUSD can arbitrarily override granular shader parameters, tools must evaluate each variant state, bake them into distinct glTF Material IDs in memory, and author the swap mapping. -* **Fallback:** The glTF extension is invalid if a variant alters underlying mesh topology. If geometry changes, or if the exporter lacks discrete state-evaluation logic, tools must safely fall back to Baseline Compliance. +* **Fallback:** The glTF extension is invalid if a variant alters underlying mesh topology or applied schemas. If geometry or structure changes, or if the exporter lacks discrete state-evaluation logic, tools must safely fall back to Baseline Compliance. ### 3.8 Lossy Conversion From 4f6d3ad860b1aaa65e59c3367e0d8c14a53f20a1 Mon Sep 17 00:00:00 2001 From: Adam Dabrowski Date: Thu, 30 Apr 2026 12:54:22 +0200 Subject: [PATCH 107/111] removed pin Signed-off-by: Adam Dabrowski --- rep.md | 1 - 1 file changed, 1 deletion(-) diff --git a/rep.md b/rep.md index 6f177e4..e2af4ac 100644 --- a/rep.md +++ b/rep.md @@ -10,7 +10,6 @@ tag: Draft category: Standard date: 2026-03-03 requires: REP 103, REP 105 -pin: true --- ## Abstract From b4c847379e1afe9182b71fd3f96be85f4947ff41 Mon Sep 17 00:00:00 2001 From: Adam Dabrowski Date: Tue, 5 May 2026 14:49:32 +0200 Subject: [PATCH 108/111] Staging for PR to official reps repository. - Renaming according to rep-0001 and proper catalogue structure for merge - Removed extensions and core schemas - these are submitted to ros-simulation/openusd-schemas instead. Signed-off-by: Adam Dabrowski --- .../reps/rep-0158/rep-0158-1.png | Bin core/ros/schema.usda | 389 ------------------ extensions/external_controller/README.md | 18 - extensions/external_controller/schema.usda | 43 -- extensions/integrated_controllers/README.md | 36 -- .../diff_drive_controller/README.md | 26 -- .../diff_drive_controller/schema.usda | 126 ------ .../README.md | 15 - .../schema.usda | 58 --- .../joint_trajectory_controller/README.md | 20 - .../joint_trajectory_controller/schema.usda | 83 ---- .../rigid_body_twist_controller/README.md | 16 - .../rigid_body_twist_controller/schema.usda | 57 --- extensions/integrated_controllers/schema.usda | 45 -- extensions/physics/NOTICE | 7 - extensions/physics/README.md | 3 - extensions/physics/schema.usda | 299 -------------- rep.md => posts/rep-0158:2006.md | 2 +- 18 files changed, 1 insertion(+), 1242 deletions(-) rename etl_pipeline_diagram.png => assets/reps/rep-0158/rep-0158-1.png (100%) delete mode 100644 core/ros/schema.usda delete mode 100644 extensions/external_controller/README.md delete mode 100644 extensions/external_controller/schema.usda delete mode 100644 extensions/integrated_controllers/README.md delete mode 100644 extensions/integrated_controllers/diff_drive_controller/README.md delete mode 100644 extensions/integrated_controllers/diff_drive_controller/schema.usda delete mode 100644 extensions/integrated_controllers/joint_state_broadcaster_controller/README.md delete mode 100644 extensions/integrated_controllers/joint_state_broadcaster_controller/schema.usda delete mode 100644 extensions/integrated_controllers/joint_trajectory_controller/README.md delete mode 100644 extensions/integrated_controllers/joint_trajectory_controller/schema.usda delete mode 100644 extensions/integrated_controllers/rigid_body_twist_controller/README.md delete mode 100644 extensions/integrated_controllers/rigid_body_twist_controller/schema.usda delete mode 100644 extensions/integrated_controllers/schema.usda delete mode 100644 extensions/physics/NOTICE delete mode 100644 extensions/physics/README.md delete mode 100644 extensions/physics/schema.usda rename rep.md => posts/rep-0158:2006.md (99%) diff --git a/etl_pipeline_diagram.png b/assets/reps/rep-0158/rep-0158-1.png similarity index 100% rename from etl_pipeline_diagram.png rename to assets/reps/rep-0158/rep-0158-1.png diff --git a/core/ros/schema.usda b/core/ros/schema.usda deleted file mode 100644 index 2ea1d5a..0000000 --- a/core/ros/schema.usda +++ /dev/null @@ -1,389 +0,0 @@ -#usda 1.0 -( - "ROS Integration Schemas for OpenUSD Simulation Asset Interoperability." - " Defines declarative, engine-agnostic API schemas for ROS interfaces" - " as specified in REP-XXXX, Section 2." - subLayers = [ - @usd/schema.usda@ - ] -) - -over "GLOBAL" ( - customData = { - string libraryName = "usdRos" - string libraryPath = "usdRos" - string libraryPrefix = "UsdRos" - dictionary libraryTokens = { - # --- Role tokens (shared by Topic, Service, Action) --- - dictionary publisher = { - string doc = """Role token indicating the interface is a publisher.""" - } - dictionary subscription = { - string doc = """Role token indicating the interface is a subscription.""" - } - dictionary server = { - string doc = """Role token indicating the interface is a server.""" - } - dictionary client = { - string doc = """Role token indicating the interface is a client.""" - } - - # --- QoS tokens --- - dictionary system_default = { - string doc = """QoS policy value deferring to the ROS 2 system default.""" - } - dictionary reliable = { - string doc = """QoS reliability policy requesting reliable delivery.""" - } - dictionary best_effort = { - string doc = """QoS reliability policy requesting best-effort delivery.""" - } - dictionary transient_local = { - string doc = """QoS durability policy requesting transient-local - storage of messages for late-joining subscriptions.""" - } - dictionary volatile_ = { - string value = "volatile" - string doc = """QoS durability policy requesting volatile (no persistence).""" - } - dictionary keep_last = { - string doc = """QoS history policy keeping only the last N messages.""" - } - dictionary keep_all = { - string doc = """QoS history policy keeping all messages.""" - } - - # --- Frame tokens --- - dictionary world = { - string doc = """Default parent frame for the top-most RosContextAPI.""" - } - } - } -) -{ -} - -# ====================================================================== -# Section 2.1 - RosContextAPI -# ====================================================================== - -class "RosContextAPI" ( - inherits = - customData = { - token apiSchemaType = "singleApply" - string className = "ContextAPI" - } - doc = """Defines the ROS 2 context for a simulation asset. - - The root prim of a ROS-interfaced simulation asset may apply this - schema to define its namespace and optionally override the DDS - domain ID. The namespace is additive in the asset hierarchy and - with a top-level namespace set during simulation deployment - (e.g. via the SpawnEntity service). - """ -) -{ - uniform string ros:context:namespace ( - customData = { - string apiName = "namespace" - } - doc = """Prefixes all topics within this scope (e.g. '/robot_1'). - The namespace is additive in the asset hierarchy.""" - ) - - uniform int ros:context:domain_id ( - customData = { - string apiName = "domainId" - } - doc = """Overrides the default ROS Domain ID for interfaces - descending from this context.""" - ) - - uniform string ros:context:parent_frame = "world" ( - customData = { - string apiName = "parentFrame" - } - doc = """Defines the parent frame_id used when the simulator - broadcasts the ground-truth transform of this context's root - prim. Only valid for the top-most context in the resolved USD - Stage and ignored otherwise.""" - ) -} - -# ====================================================================== -# Section 2.4 - RosTopicAPI -# ====================================================================== - -class "RosTopicAPI" ( - inherits = - customData = { - token apiSchemaType = "singleApply" - string className = "TopicAPI" - } - doc = """Applied to prims exchanging streaming ROS 2 data. - - Simulators spawn the corresponding publisher or subscription at - runtime. Robot-wide interfaces go on or beneath the RosContextAPI - prim; sensor interfaces go on a child Xform of the physical link, - one interface per prim. Interface prims must reside outside payloads - and do not generate TF frames. - """ -) -{ - # ------------------------------------------------------------------ - # Core Attributes (Required) - # ------------------------------------------------------------------ - - uniform token ros:topic:role ( - customData = { - string apiName = "role" - } - allowedTokens = ["publisher", "subscription"] - doc = """Defines whether this interface acts as a publisher or a - subscription.""" - ) - - uniform string ros:topic:name ( - customData = { - string apiName = "name" - } - doc = """The topic name, relative to the active ROS 2 namespace - inherited from the nearest ancestor RosContextAPI. Must adhere - to ROS 2 topic naming rules (alphanumeric, underscores, and - forward slashes only; cannot start with a number).""" - ) - - uniform string ros:topic:type ( - customData = { - string apiName = "type" - } - doc = """The ROS 2 message type string (e.g. 'sensor_msgs/msg/Image'). - Simulators must attempt to resolve this type dynamically against the - sourced ROS 2 environment. If the type is not found, the simulator - must safely disable this interface and emit a warning.""" - ) - - uniform double ros:topic:publish_rate ( - customData = { - string apiName = "publishRate" - } - doc = """Target publication frequency in Hz. Required for publishers; - ignored for subscriptions.""" - ) - - # ------------------------------------------------------------------ - # Optional attributes - # ------------------------------------------------------------------ - - uniform string ros:topic:override_frame_id ( - customData = { - string apiName = "overrideFrameId" - } - doc = """If non-empty, overrides the Header.frame_id populated in - the published message. When empty or omitted, simulators use the - TF frame name of the nearest ancestor that is a TF frame - (implicit or explicit). Only relevant for message types - containing a std_msgs/Header; ignored otherwise.""" - ) - - uniform bool ros:topic:starts_enabled = true ( - customData = { - string apiName = "startsEnabled" - } - doc = """If false, simulators must skip active instantiation of this - interface at load time. Allows VariantSets or composition overrides - to declaratively toggle interfaces. Runtime lifecycle management - remains the simulator's responsibility.""" - ) - - # ------------------------------------------------------------------ - # Quality of Service (QoS) Attributes - # ------------------------------------------------------------------ - - uniform bool ros:topic:qos:match_publisher = false ( - customData = { - string apiName = "qosMatchPublisher" - } - doc = """For subscriptions only. If true, the simulator bridge must - attempt to use ROS 2 QoS matching to adapt to the discovered - publisher, ignoring explicit reliability and durability settings.""" - ) - - uniform token ros:topic:qos:reliability = "system_default" ( - customData = { - string apiName = "qosReliability" - } - allowedTokens = ["system_default", "reliable", "best_effort"] - doc = """Maps to rmw_qos_profile_t reliability policy. As per - REP 2003, simulated sensors should default to 'system_default' - which maps to best-effort.""" - ) - - uniform token ros:topic:qos:durability = "system_default" ( - customData = { - string apiName = "qosDurability" - } - allowedTokens = ["system_default", "transient_local", "volatile"] - doc = """Maps to rmw_qos_profile_t durability policy. Map - publishers should use 'transient_local'.""" - ) - - uniform token ros:topic:qos:history = "system_default" ( - customData = { - string apiName = "qosHistory" - } - allowedTokens = ["system_default", "keep_last", "keep_all"] - doc = """Maps to rmw_qos_profile_t history policy.""" - ) - - uniform int ros:topic:qos:depth = 10 ( - customData = { - string apiName = "qosDepth" - } - doc = """Queue size. Evaluated only when history is 'keep_last'.""" - ) -} - -# ====================================================================== -# Section 2.5 - RosServiceAPI -# ====================================================================== - -class "RosServiceAPI" ( - inherits = - customData = { - token apiSchemaType = "singleApply" - string className = "ServiceAPI" - } - doc = """Applied to prims handling synchronous ROS 2 requests. - - Simulators spawn the corresponding server or client at runtime. - Same placement, resolution, and TF exclusion rules as RosTopicAPI. - """ -) -{ - uniform token ros:service:role ( - customData = { - string apiName = "role" - } - allowedTokens = ["server", "client"] - doc = """Defines whether this interface acts as a server or a - client. Simulation assets are typically servers.""" - ) - - uniform string ros:service:name ( - customData = { - string apiName = "name" - } - doc = """The service name, relative to the active ROS 2 namespace. - Must adhere to ROS 2 naming rules.""" - ) - - uniform string ros:service:type ( - customData = { - string apiName = "type" - } - doc = """The ROS 2 service type (e.g. 'std_srvs/srv/SetBool'). - Simulators must resolve dynamically; disable on failure.""" - ) - - uniform bool ros:service:starts_enabled = true ( - customData = { - string apiName = "startsEnabled" - } - doc = """If false, simulators must skip active instantiation of this - interface at load time. Allows VariantSets or composition overrides - to declaratively toggle interfaces. Runtime lifecycle management - remains the simulator's responsibility.""" - ) -} - -# ====================================================================== -# Section 2.6 - RosActionAPI -# ====================================================================== - -class "RosActionAPI" ( - inherits = - customData = { - token apiSchemaType = "singleApply" - string className = "ActionAPI" - } - doc = """Applied to prims handling asynchronous, long-running ROS 2 behaviors. - - Simulators spawn the corresponding server or client at runtime. - Same placement, resolution, and TF exclusion rules as RosTopicAPI. - """ -) -{ - uniform token ros:action:role ( - customData = { - string apiName = "role" - } - allowedTokens = ["server", "client"] - doc = """Defines whether this interface acts as a server or a - client. Simulation assets are typically servers.""" - ) - - uniform string ros:action:name ( - customData = { - string apiName = "name" - } - doc = """The action name, relative to the active ROS 2 namespace. - Must adhere to ROS 2 naming rules.""" - ) - - uniform string ros:action:type ( - customData = { - string apiName = "type" - } - doc = """The ROS 2 action type - (e.g. 'control_msgs/action/FollowJointTrajectory'). - Simulators must resolve dynamically; disable on failure.""" - ) - - uniform bool ros:action:starts_enabled = true ( - customData = { - string apiName = "startsEnabled" - } - doc = """If false, simulators must skip active instantiation of this - interface at load time. Allows VariantSets or composition overrides - to declaratively toggle interfaces. Runtime lifecycle management - remains the simulator's responsibility.""" - ) -} - -# ====================================================================== -# Section 2.7 - RosFrameAPI -# ====================================================================== - -class "RosFrameAPI" ( - inherits = - customData = { - token apiSchemaType = "singleApply" - string className = "FrameAPI" - } - doc = """Explicit TF frame broadcasting for non-physical dummy frames. - - Apply this schema to UsdGeomXform prims that need TF frames but do - not possess a PhysicsRigidBodyAPI (e.g. camera_optical_frame, - grasp_point). Physical links connected via joints get implicit TF - broadcasting and do not need this schema. - """ -) -{ - uniform string ros:frame:id ( - customData = { - string apiName = "id" - } - doc = """Overrides the TF frame name. If omitted, the validated - Prim name is used as the frame_id.""" - ) - - uniform bool ros:frame:static = true ( - customData = { - string apiName = "static" - } - doc = """Defines the broadcast destination. If true, the simulator - broadcasts to /tf_static. If false (e.g. an Xform animated by - USD TimeSamples), the simulator broadcasts to /tf.""" - ) -} diff --git a/extensions/external_controller/README.md b/extensions/external_controller/README.md deleted file mode 100644 index b7a4fbe..0000000 --- a/extensions/external_controller/README.md +++ /dev/null @@ -1,18 +0,0 @@ -# REP XXXX -- OpenUSD Conventions for Simulation Asset Interoperability - External Controller Extension - -## Abstract - -This document defines conventions for the external control interface in OpenUSD-based robot simulation, where the control algorithm runs outside the simulator. -It enables test scenarios where the simulator provides a physics digital twin of the robot and exposes its low-level hardware interfaces (e.g. joint position, velocity, and effort command interfaces) to an external control entity. - -## External Control Interfaces - -The ROS 2 external control `RosControlExternalAPI` 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 a controller. -A simulator loading a prim with this schema should establish a connection, load a controller plugin, spawn a controller instance, or set up a hardware-in-the-loop connection to the robot controller, -and expose the control and state interfaces to the control entity. - -## Tools - -### Schema Definition -The normative OpenUSD schema definition for `RosControlExternalAPI` is provided in `schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. diff --git a/extensions/external_controller/schema.usda b/extensions/external_controller/schema.usda deleted file mode 100644 index 5f914d6..0000000 --- a/extensions/external_controller/schema.usda +++ /dev/null @@ -1,43 +0,0 @@ -#usda 1.0 -( - "ROS Integration Schemas for OpenUSD Simulation Asset Interoperability." - " Defines declarative, engine-agnostic API schemas for ROS external" - " control interfaces as specified in REP-XXXX, Section 1.1." - subLayers = [ - @usd/schema.usda@ - ] -) - -over "GLOBAL" ( - customData = { - string libraryName = "usdRosControlExternal" - string libraryPath = "." - string libraryPrefix = "Usd" - dictionary libraryTokens = { - } - } -) -{ -} - -# ====================================================================== -# RosControlExternalAPI -# ====================================================================== - -class "RosControlExternalAPI" ( - inherits = - customData = { - token apiSchemaType = "singleApply" - string className = "RosControlExternalAPI" - } - doc = """Base schema for exposing robot control interfaces to external control algorithms. - - Applied (via 'prepend apiSchemas') by simulator-specific schemas to - identify prims whose joint state and command interfaces should be - exposed to an external control entity (e.g. a ros2_control - hardware_interface plugin, an inter-process controller, or a - hardware-in-the-loop connection). - """ -) -{ -} diff --git a/extensions/integrated_controllers/README.md b/extensions/integrated_controllers/README.md deleted file mode 100644 index 835e813..0000000 --- a/extensions/integrated_controllers/README.md +++ /dev/null @@ -1,36 +0,0 @@ -# REP XXXX -- OpenUSD Conventions for Simulation Asset Interoperability - Integrated Control Extension - -## Abstract - -This document defines conventions for simulating robotic systems in OpenUSD using integrated controller algorithms running inside the simulation environment. -This enables application-level testing, where the robotic system is simulated as a whole, including its physical properties, kinematics, and dynamics. -In this approach the controller is integrated in the simulator codebase and managed by parameters of the prim and ROS communication. - -## Integrated Controller Simulation - -`RosControlIntegratedAPI` allows instantiating robot controllers directly in the simulated scene. -It must reference one or more prims that have [RosTopicAPI](../../rep.md#24-topic-interface-rostopicapi), [RosServiceAPI](../../rep.md#25-service-interface-rosserviceapi) or [RosActionAPI](../../rep.md#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. -For example, `simulatorXYZ::RosCustomTwistControllerAPI` would include `RosControlIntegratedAPI` as a built-in and reference prims: -- `RosTopicAPI` for subscription of control messages. -- `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 a controller have at least one of the following API schemas applied: `RosTopicAPI`, `RosServiceAPI` or `RosActionAPI`. - -### Built-in Controllers - -The following schemas are built-in controller schemas that include `RosControlIntegratedAPI` as a built-in via `prepend apiSchemas`. -Simulators may implement these schemas to provide a standardized control interface for common use cases, -such as different robot locomotion paradigms (e.g. Ackermann steering) or application-specific interfaces (e.g. joint control for robot policies). -The following controllers are proposed as a minimal baseline for initial compliance. -The parameters and logic should follow established controllers in the ROS ecosystem and allow bootstrapping robot simulation with minimal custom development. -Simulators may implement additional controllers as needed, but these four are proposed as the baseline for application-level simulation compliance. -The implementation should support multi-robot simulation and control by leveraging namespaces. - -## Controller Schemas - -Individual controllers have their schema definitions in `/schema.usda`. The sibling directories of this file each contain one such controller. - -## Schema Definition - -The OpenUSD schema definition for `RosControlIntegratedAPI` is provided in `schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. diff --git a/extensions/integrated_controllers/diff_drive_controller/README.md b/extensions/integrated_controllers/diff_drive_controller/README.md deleted file mode 100644 index a646172..0000000 --- a/extensions/integrated_controllers/diff_drive_controller/README.md +++ /dev/null @@ -1,26 +0,0 @@ -# RosControlDiffDriveAPI - -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`: relationship targeting a prim with the RosTopicAPI with `role="subscription"` that provides the velocity commands for this controller. -- `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. Exposed as dynamic parameter. -- `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². - -## Tools - -### Schema Definition -The normative OpenUSD schema definition for `RosControlDiffDriveAPI` is provided in `schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. diff --git a/extensions/integrated_controllers/diff_drive_controller/schema.usda b/extensions/integrated_controllers/diff_drive_controller/schema.usda deleted file mode 100644 index f5f7fa4..0000000 --- a/extensions/integrated_controllers/diff_drive_controller/schema.usda +++ /dev/null @@ -1,126 +0,0 @@ -#usda 1.0 -( - "ROS Integration Schemas for OpenUSD Simulation Asset Interoperability." - " Defines declarative, engine-agnostic API schemas for the differential" - " drive controller as specified in REP-XXXX, Section 1.2.1.2." - subLayers = [ - @usd/schema.usda@ - ] -) - -over "GLOBAL" ( - customData = { - string libraryName = "usdRosControlDiffDrive" - string libraryPath = "." - string libraryPrefix = "Usd" - dictionary libraryTokens = { - } - } -) -{ -} - -# ====================================================================== -# RosControlDiffDriveAPI -# ====================================================================== - -class "RosControlDiffDriveAPI" ( - inherits = - prepend apiSchemas = ["RosControlIntegratedAPI"] - customData = { - token apiSchemaType = "singleApply" - string className = "RosControlDiffDriveAPI" - } - doc = """Controls a differential drive robot via geometry_msgs/Twist messages. - - Subscribes to a Twist topic, converts commanded linear and angular - velocities into individual wheel velocities, and applies them to - wheel joint prims with UsdPhysicsDriveAPI. Publishes odometry data - as nav_msgs/Odometry. Implementation should follow logic similar to - the diff_drive_controller in ros2_controllers. - """ -) -{ - rel ros:diff_drive:subscriber ( - customData = { - string apiName = "subscriber" - } - doc = """Reference to a prim with RosTopicAPI configured as a - subscription for geometry_msgs/Twist velocity commands.""" - ) - - rel ros:diff_drive:odom ( - customData = { - string apiName = "odom" - } - doc = """Reference to a prim with RosTopicAPI configured as a - publisher for nav_msgs/Odometry data.""" - ) - - rel ros:diff_drive:left_wheels ( - customData = { - string apiName = "leftWheels" - } - doc = """References to prims with UsdPhysicsDriveAPI representing - the left wheel joints.""" - ) - - rel ros:diff_drive:right_wheels ( - customData = { - string apiName = "rightWheels" - } - doc = """References to prims with UsdPhysicsDriveAPI representing - the right wheel joints.""" - ) - - uniform double ros:diff_drive:wheel_separation ( - customData = { - string apiName = "wheelSeparation" - } - doc = """Distance between the left and right wheel contact points - in meters.""" - ) - - uniform double ros:diff_drive:wheel_radius ( - customData = { - string apiName = "wheelRadius" - } - doc = """Radius of the wheels in meters.""" - ) - - uniform double ros:diff_drive:cmd_vel_timeout = 0.5 ( - customData = { - string apiName = "cmdVelTimeout" - } - doc = """Timeout in seconds after which a velocity command is - considered stale and wheel velocities are zeroed.""" - ) - - uniform double ros:diff_drive:linear:x:max_velocity ( - customData = { - string apiName = "linearXMaxVelocity" - } - doc = """Maximum linear velocity along the X axis in m/s.""" - ) - - uniform double ros:diff_drive:linear:x:max_acceleration ( - customData = { - string apiName = "linearXMaxAcceleration" - } - doc = """Maximum linear acceleration along the X axis in m/s².""" - ) - - uniform double ros:diff_drive:angular:z:max_velocity ( - customData = { - string apiName = "angularZMaxVelocity" - } - doc = """Maximum angular velocity around the Z axis in rad/s.""" - ) - - uniform double ros:diff_drive:angular:z:max_acceleration ( - customData = { - string apiName = "angularZMaxAcceleration" - } - doc = """Maximum angular acceleration around the Z axis in rad/s².""" - ) -} diff --git a/extensions/integrated_controllers/joint_state_broadcaster_controller/README.md b/extensions/integrated_controllers/joint_state_broadcaster_controller/README.md deleted file mode 100644 index cffcde2..0000000 --- a/extensions/integrated_controllers/joint_state_broadcaster_controller/README.md +++ /dev/null @@ -1,15 +0,0 @@ -# RosControlJointStateBroadcasterAPI - -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#210-custom-names-to-ros-joints) in `ros:joint:name` -property of the joint prims and use it for mapping joints in the simulator to those in robot description or application. - -- `rel ros:joint_state_broadcaster:publisher`: relationship targeting a prim with the RosTopicAPI with `role="publisher"` for joint state data. -- `rel ros:joint_state_broadcaster:joints`: References to prims with `UsdPhysicsJoint` representing the joints whose states are to be broadcast. -- `string ros:joint_state_broadcaster:frame_id`: The TF frame ID to be used in the published JointState messages. - -## Tools - -### Schema Definition -The normative OpenUSD schema definition for `RosControlJointStateBroadcasterAPI` is provided in `schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. diff --git a/extensions/integrated_controllers/joint_state_broadcaster_controller/schema.usda b/extensions/integrated_controllers/joint_state_broadcaster_controller/schema.usda deleted file mode 100644 index cf78fc6..0000000 --- a/extensions/integrated_controllers/joint_state_broadcaster_controller/schema.usda +++ /dev/null @@ -1,58 +0,0 @@ -#usda 1.0 -( - "ROS Integration Schemas for OpenUSD Simulation Asset Interoperability." - " Defines declarative, engine-agnostic API schemas for the joint state" - " broadcaster controller as specified in REP-XXXX, Section 1.2.1.4." - subLayers = [ - @usd/schema.usda@ - ] -) - -over "GLOBAL" ( - customData = { - string libraryName = "usdRosControlJointStateBroadcaster" - string libraryPath = "." - string libraryPrefix = "Usd" - dictionary libraryTokens = { - } - } -) -{ -} - -# ====================================================================== -# RosControlJointStateBroadcasterAPI -# ====================================================================== - -class "RosControlJointStateBroadcasterAPI" ( - inherits = - prepend apiSchemas = ["RosControlIntegratedAPI"] - customData = { - token apiSchemaType = "singleApply" - string className = "RosControlJointStateBroadcasterAPI" - } - doc = """Reads joint states and publishes them as sensor_msgs/JointState messages. - - Implementation should follow logic similar to the - joint_state_broadcaster in ros2_controllers. - """ -) -{ - rel ros:joint_state_broadcaster:publisher ( - customData = { - string apiName = "publisher" - } - doc = """Reference to a prim with RosTopicAPI configured as a - publisher for sensor_msgs/JointState messages.""" - ) - - rel ros:joint_state_broadcaster:joints ( - customData = { - string apiName = "joints" - } - doc = """References to prims with UsdPhysicsJoint representing - the joints whose states are to be broadcast. Simulators must use - the ros:joint:name custom property for joint name mapping, - falling back to the prim name if absent.""" - ) -} diff --git a/extensions/integrated_controllers/joint_trajectory_controller/README.md b/extensions/integrated_controllers/joint_trajectory_controller/README.md deleted file mode 100644 index 492aa60..0000000 --- a/extensions/integrated_controllers/joint_trajectory_controller/README.md +++ /dev/null @@ -1,20 +0,0 @@ -# RosControlJointTrajectoryAPI - -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#210-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 `UsdPhysicsJoint`. -- `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. Exposed as dynamic parameter. -- `double ros:joint_trajectory:timeout`: Maximum time allowed to reach the trajectory goal. - -## Tools - -### Schema Definition -The normative OpenUSD schema definition for `RosControlJointTrajectoryAPI` is provided in `schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. diff --git a/extensions/integrated_controllers/joint_trajectory_controller/schema.usda b/extensions/integrated_controllers/joint_trajectory_controller/schema.usda deleted file mode 100644 index 484480d..0000000 --- a/extensions/integrated_controllers/joint_trajectory_controller/schema.usda +++ /dev/null @@ -1,83 +0,0 @@ -#usda 1.0 -( - "ROS Integration Schemas for OpenUSD Simulation Asset Interoperability." - " Defines declarative, engine-agnostic API schemas for the joint" - " trajectory controller as specified in REP-XXXX, Section 1.2.1.3." - subLayers = [ - @usd/schema.usda@ - ] -) - -over "GLOBAL" ( - customData = { - string libraryName = "usdRosControlJointTrajectory" - string libraryPath = "." - string libraryPrefix = "Usd" - dictionary libraryTokens = { - } - } -) -{ -} - -# ====================================================================== -# RosControlJointTrajectoryAPI -# ====================================================================== - -class "RosControlJointTrajectoryAPI" ( - inherits = - prepend apiSchemas = ["RosControlIntegratedAPI"] - customData = { - token apiSchemaType = "singleApply" - string className = "RosControlJointTrajectoryAPI" - } - doc = """Executes joint trajectories via control_msgs/FollowJointTrajectory actions. - - Accepts action goals and commands the simulator to follow the - specified joint trajectory. Implementation should follow logic - similar to the joint_trajectory_controller in ros2_controllers. - """ -) -{ - rel ros:joint_trajectory:server ( - customData = { - string apiName = "server" - } - doc = """Reference to a prim with RosActionAPI configured as a - server for control_msgs/FollowJointTrajectory action goals.""" - ) - - rel ros:joint_trajectory:command_joints ( - customData = { - string apiName = "commandJoints" - } - doc = """References to prims with UsdPhysicsJoint representing - the joints to be commanded along the trajectory. Simulators must - use the ros:joint:name custom property for joint name mapping, - falling back to the prim name if absent.""" - ) - - uniform double ros:joint_trajectory:action_monitor_rate ( - customData = { - string apiName = "actionMonitorRate" - } - doc = """Frequency in Hz at which trajectory execution progress - is monitored.""" - ) - - uniform double ros:joint_trajectory:stopped_velocity_tolerance ( - customData = { - string apiName = "stoppedVelocityTolerance" - } - doc = """Velocity tolerance at the end of the trajectory below - which the controlled system is considered stopped.""" - ) - - uniform double ros:joint_trajectory:timeout ( - customData = { - string apiName = "timeout" - } - doc = """Maximum time in seconds allowed to reach the trajectory - goal before the action is aborted.""" - ) -} diff --git a/extensions/integrated_controllers/rigid_body_twist_controller/README.md b/extensions/integrated_controllers/rigid_body_twist_controller/README.md deleted file mode 100644 index 895aefd..0000000 --- a/extensions/integrated_controllers/rigid_body_twist_controller/README.md +++ /dev/null @@ -1,16 +0,0 @@ -# RosControlRigidBodyTwistAPI - -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. -This provides a general-purpose controller for applying velocity commands to a rigid body without wheel kinematics or joint decomposition. - -- `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` to which the commanded velocities are applied. - -## Tools - -### Schema Definition -The normative OpenUSD schema definition for `RosControlRigidBodyTwistAPI` is provided in `schema.usda`. It can be used with `usdGenSchema` to produce either a codeless plugin (schema awareness and fallback values only) or full C++ and Python bindings for simulator integration. diff --git a/extensions/integrated_controllers/rigid_body_twist_controller/schema.usda b/extensions/integrated_controllers/rigid_body_twist_controller/schema.usda deleted file mode 100644 index 79f0f62..0000000 --- a/extensions/integrated_controllers/rigid_body_twist_controller/schema.usda +++ /dev/null @@ -1,57 +0,0 @@ -#usda 1.0 -( - "ROS Integration Schemas for OpenUSD Simulation Asset Interoperability." - " Defines declarative, engine-agnostic API schemas for the rigid body" - " twist controller as specified in REP-XXXX, Section 1.2.1.1." - subLayers = [ - @usd/schema.usda@ - ] -) - -over "GLOBAL" ( - customData = { - string libraryName = "usdRosControlRigidBodyTwist" - string libraryPath = "." - string libraryPrefix = "Usd" - dictionary libraryTokens = { - } - } -) -{ -} - -# ====================================================================== -# RosControlRigidBodyTwistAPI -# ====================================================================== - -class "RosControlRigidBodyTwistAPI" ( - inherits = - prepend apiSchemas = ["RosControlIntegratedAPI"] - customData = { - token apiSchemaType = "singleApply" - string className = "RosControlRigidBodyTwistAPI" - } - doc = """Controls a rigid body via geometry_msgs/Twist messages. - - Subscribes to a Twist topic and applies the commanded linear and - angular velocities directly to a rigid body in the physics engine, - with optional velocity and acceleration limits. - """ -) -{ - rel ros:rigid_body_twist:subscriber ( - customData = { - string apiName = "subscriber" - } - doc = """Reference to a prim with RosTopicAPI configured as a - subscription for geometry_msgs/Twist control messages.""" - ) - - rel ros:rigid_body_twist:body ( - customData = { - string apiName = "body" - } - doc = """Reference to a prim with UsdPhysicsRigidBodyAPI to which - the commanded velocities are applied.""" - ) -} diff --git a/extensions/integrated_controllers/schema.usda b/extensions/integrated_controllers/schema.usda deleted file mode 100644 index c1c5766..0000000 --- a/extensions/integrated_controllers/schema.usda +++ /dev/null @@ -1,45 +0,0 @@ -#usda 1.0 -( - "ROS Integration Schemas for OpenUSD Simulation Asset Interoperability." - " Defines the base API schema for integrated (application-level) robot" - " controllers as specified in REP-XXXX, Section 1.2." - subLayers = [ - @usd/schema.usda@ - ] -) - -over "GLOBAL" ( - customData = { - string libraryName = "usdRosControl" - string libraryPath = "." - string libraryPrefix = "Usd" - dictionary libraryTokens = { - } - } -) -{ -} - -# ====================================================================== -# RosControlIntegratedAPI -# ====================================================================== - -class "RosControlIntegratedAPI" ( - inherits = - customData = { - token apiSchemaType = "singleApply" - string className = "RosControlIntegratedAPI" - } - doc = """Base schema for integrated (application-level) robot controllers. - - Included as a built-in via 'prepend apiSchemas' by simulator-specific - or standardized controller schemas that run the controller logic - inside the simulator. All prims referenced by a controller that - inherits this schema must have at least one of RosTopicAPI, - RosServiceAPI, or RosActionAPI applied. USD does not enforce this - constraint at the schema level; simulators are responsible for - runtime validation. - """ -) -{ -} diff --git a/extensions/physics/NOTICE b/extensions/physics/NOTICE deleted file mode 100644 index acb91f4..0000000 --- a/extensions/physics/NOTICE +++ /dev/null @@ -1,7 +0,0 @@ -Multiple schemas in schema.usda were adapted from Newton: https://github.com/newton-physics/newton-usd-schemas - -Changes include: -- Selection of schemas (omitting solver-specific, global parameters, and control-related). -- Renaming Newton to ExtendedPhysics, newton: to ext_physics: -- Adding sub-namespaces within (e.g. ext_physics:mimic) -- Adjusting some comments. \ No newline at end of file diff --git a/extensions/physics/README.md b/extensions/physics/README.md deleted file mode 100644 index 4815400..0000000 --- a/extensions/physics/README.md +++ /dev/null @@ -1,3 +0,0 @@ -# Extended Physics Schema - -This schema provides an extended feature set for OpenUSD physics. It draws heavily from work on [Newton Schemas](https://github.com/newton-physics/newton-usd-schemas) while ensuring neutral naming and focus on full interoperability. diff --git a/extensions/physics/schema.usda b/extensions/physics/schema.usda deleted file mode 100644 index 5c2495b..0000000 --- a/extensions/physics/schema.usda +++ /dev/null @@ -1,299 +0,0 @@ -#usda 1.0 -( - "Extended Physics Schemas for OpenUSD Simulation Asset Interoperability." - " Defines declarative, engine-agnostic physics features, " - " meant to extend OpenUSD Physics while following REP-XXXX rules." - subLayers = [ - @usd/schema.usda@ - ] -) - -over "GLOBAL" ( - customData = { - string libraryName = "usdExtendedPhysics" - string libraryPath = "." - } -) -{ -} - -# ====================================================================== -# Extended Physics Schemas -# -# Physics extension schemas are leveraging emerging simulation features -# without violating vendor-neutrality. They are meant to be -# "Incubating Schemas", based on upstream proposals and pending inclusion -# into the OpenUSD standard. -# ====================================================================== - -# Schemas adapted from Newton upstream: https://github.com/newton-physics/newton-usd-schemas - -class "ExtendedPhysicsMaterialAPI" ( - inherits = - customData = { - string className = "MaterialAPI" - token apiSchemaType = "singleApply" - } - prepend apiSchemas = ["PhysicsMaterialAPI"] - doc = """ExtendedPhysicsMaterialAPI applies on top of a Material, providing extra physical material attributes. - - By applying this schema, the prim also inherits the `PhysicsMaterialAPI` schema.""" -) -{ - float ext_physics:material:torsionalFriction = 0.25 ( - doc = """Torsional friction coefficient (resistance to spinning at a contact point). - - Range: [0, inf) - Units: dimensionless""" - limits = { - dictionary hard = { - float minimum = 0 - } - } - ) - - float ext_physics:material:rollingFriction = 0.0005 ( - doc = """Rolling friction coefficient (resistance to rolling motion). - - Range: [0, inf) - Units: dimensionless""" - limits = { - dictionary hard = { - float minimum = 0 - } - } - ) -} - -class "ExtendedPhysicsMimicAPI" ( - inherits = - customData = { - string className = "MimicAPI" - token apiSchemaType = "singleApply" - } - doc = """ExtendedPhysicsMimicAPI applies on top of a PhysicsJoint, adding additional constraints to mimic the DOFs of another joint. - - A mimic constraint enforces that `joint0 = offset + multiplier * joint1` for the joint DOFs, - where `joint0` is this joint (the follower) and `joint1` (the leader) is specified via the `ext_physics:mimic:joint` relationship. - - The behavior on multi-DOF joints is undefined. The mimic constraint will be applied to each DOF independently, - but as the coefficients are shared across all DOFs, the units for translational and rotational DOFs will be mixed. - Therefore, it is recommended to only use this API on single-DOF joints. - """ -) -{ - bool ext_physics:mimic:enabled = true ( - doc = """Whether the mimic constraint is active. - - When disabled, the follower joint moves independently, as though the mimic constraint was not applied.""" - ) - - rel ext_physics:mimic:joint ( - doc = "Joint that will be mimicked." - ) - - float ext_physics:mimic:offset = 0.0 ( - doc = """Offset added after scaling the leader joint's position/angle. - - Range: (-inf, inf) - Units: distance or degrees (matches the joint type for single-DOF joints)""" - ) - - float ext_physics:mimic:multiplier = 1.0 ( - doc = """Scale factor applied to the leader joint's position/angle. - - A value of 1.0 means the follower tracks the leader exactly (plus `ext_physics:mimic:offset`), - while negative values reverse the direction. - - Range: (-inf, inf) - Units: dimensionless""" - ) -} - - -class "ExtendedPhysicsActuatorAPI" ( - inherits = - customData = { - string className = "ActuatorAPI" - token apiSchemaType = "singleApply" - } - doc = """Defines a physical actuator that computes effort to apply to a joint. - - An actuator computes effort (i.e. force/torque for linear/rotational actuators) to apply - to a PhysicsRevoluteJoint or PhysicsPrismaticJoint specified via the `ext_physics:actuator:targets` - relationship. Future versions may expand the set of valid target types. - - Control schemas should use it to drive the actuator, - and limits are applied through `ExtendedPhysicsActuatorClampingBaseAPI`. - - Note: Extended Physics actuators use radians, diverging from UsdPhysicsDriveAPI which uses degrees. - Actuator attributes are also documented in joint space, though this is not enforced, - and users may scale attributes to fit their own convention by updating their parser - and/or integration code accordingly. - - - """ -) -{ - rel ext_physics:actuator:targets ( - doc = """The joint driven by this actuator. - - The relationship must be authored. Parsers should raise an error if no target - is provided; users should deactivate the prim if they want to disable the actuator. - - Currently only the first target is honored, and it must identify either a - `PhysicsRevoluteJoint` or `PhysicsPrismaticJoint`. - - Multi-DOF PhysicsJoints are not supported, even when locked via LimitAPIs to a single axis. - """ - ) -} - -class "ExtendedPhysicsActuatorClampingBaseAPI" ( - inherits = - customData = { - string className = "ActuatorClampingBaseAPI" - token apiSchemaType = "singleApply" - } - doc = """Base API for all actuator clamping strategies. - - Any number of ExtendedPhysicsActuatorClampingBaseAPI derived schemas - (e.g. ExtendedPhysicsMaxEffortClampingAPI) may be applied to an ExtendedPhysicsActuatorAPI - to constrain actuator output effort (i.e. force/torque for linear/rotational actuators). - The order of clamping is not guaranteed to be preserved thus clamping operations must be order independent. - - Check prim.HasAPI('ExtendedPhysicsActuatorClampingBaseAPI') to detect whether any clamping is present. - """ -) -{ -} - -class "ExtendedPhysicsMaxEffortClampingAPI" ( - inherits = - customData = { - string className = "MaxEffortClampingAPI" - token apiSchemaType = "singleApply" - } - prepend apiSchemas = ["ExtendedPhysicsActuatorClampingBaseAPI"] - doc = """Symmetric clamp on actuator output effort. - - Clamps the actuator output to the range [-maxEffort, +maxEffort]. - """ -) -{ - float ext_physics:clamp_effort:maxEffort = inf ( - doc = """Maximum output effort limit (in joint space). - - The actuator output is clamped to the range [-maxEffort, +maxEffort]. - - Range: [0, inf) - Units: force or torque""" - limits = { - dictionary hard = { - float minimum = 0 - } - } - ) -} - -class "ExtendedPhysicsDCMotorClampingAPI" ( - inherits = - customData = { - string className = "DCMotorClampingAPI" - token apiSchemaType = "singleApply" - } - prepend apiSchemas = ["ExtendedPhysicsActuatorClampingBaseAPI"] - doc = """DC motor four-quadrant effort clamp. - - A four-quadrant effort clamp based on the DC motor effort-speed characteristic: - - effort_max(vel) = min(saturationEffort * (1 - vel / velocityLimit), maxMotorEffort) - effort_min(vel) = max(saturationEffort * (-1 - vel / velocityLimit), -maxMotorEffort) - - At zero velocity the motor can produce up to saturationEffort (capped by maxMotorEffort). - As velocity approaches velocityLimit, available effort drops to zero in both directions. - """ -) -{ - float ext_physics:clamp_motor:maxEffort = inf ( - doc = """Effort limit for the effort-speed curve (in joint space). - - Caps the velocity-dependent effort envelope. - - Range: [0, inf) - Units: force or torque""" - limits = { - dictionary hard = { - float minimum = 0 - } - } - ) - - float ext_physics:clamp_motor:saturationEffort = inf ( - doc = """Peak motor effort at stall (zero velocity). - - This is the maximum effort the motor can produce when not spinning, - before being capped by maxEffort. - - Range: [0, inf) - Units: force or torque""" - limits = { - dictionary hard = { - float minimum = 0 - } - } - ) - - float ext_physics:clamp_motor:velocityLimit = inf ( - doc = """Maximum no-load joint velocity for the effort-speed curve. - - At this velocity, the motor can produce zero effort in the direction - of motion due to losses such as back-EMF. A value of inf disables the effort-speed - saturation effect. - - Range: (0, inf) - Units: distance / seconds or radians / seconds""" - limits = { - dictionary hard = { - float minimum = 0 - } - } - ) -} - -class "ExtendedPhysicsPositionBasedClampingAPI" ( - inherits = - customData = { - string className = "PositionBasedClampingAPI" - token apiSchemaType = "singleApply" - } - prepend apiSchemas = ["ExtendedPhysicsActuatorClampingBaseAPI"] - doc = """Position-dependent effort clamping via lookup table. - - Provides position-dependent effort limits interpolated from a lookup table - to model actuators whose maximum output effort varies with joint position. - - Sampling rules: - - Inputs strictly between adjacent (position, effort) entries are linearly interpolated. - - Inputs at or below ext_physics:clamp_position:lookupPositions[0] clamp to ext_physics:clamp_position:lookupEfforts[0]. - - Inputs at or above ext_physics:clamp_position:lookupPositions[-1] clamp to ext_physics:clamp_position:lookupEfforts[-1]. - - For rotational actuators, positions do not wrap periodically. - """ -) -{ - float[] ext_physics:clamp_position:lookupPositions = [] ( - doc = """Sorted joint positions for the effort lookup table. - - Must be monotonically increasing and the same length as ext_physics:clamp_position:lookupEfforts. - - Units: distance or radians""" - ) - - float[] ext_physics:clamp_position:lookupEfforts = [] ( - doc = """Maximum output effort values corresponding to each entry in ext_physics:clamp_position:lookupPositions. - - Must be the same length as ext_physics:clamp_position:lookupPositions. - - Units: force or torque""" - ) -} diff --git a/rep.md b/posts/rep-0158:2006.md similarity index 99% rename from rep.md rename to posts/rep-0158:2006.md index e2af4ac..83f49b2 100644 --- a/rep.md +++ b/posts/rep-0158:2006.md @@ -66,7 +66,7 @@ This REP adopts the ASWF Guidelines for Structuring USD Assets. #### 1.2.1 Schema Isolation and Functional Layering (The ETL Pipeline) -![Extract-Transform-Load Pipeline for Robots in USD](etl_pipeline_diagram.png) +![Extract-Transform-Load Pipeline for Robots in USD](/assets/reps/rep-0158/rep-0158-1.png) *Figure 1: The Extract-Transform-Load (ETL) composition pipeline for OpenUSD robotics assets. Source: [NVIDIA Developer Blog](https://developer.nvidia.com/blog/using-openusd-for-modular-and-scalable-robotic-simulation-and-development/)* As illustrated in Figure 1, assets should be divided into functional layers composed via References and Payloads: From 897d461d04a7ccaddfe5d717e9cb13aa6e2466fc Mon Sep 17 00:00:00 2001 From: Adam Dabrowski Date: Tue, 5 May 2026 14:55:05 +0200 Subject: [PATCH 109/111] Added link to openusd-schemas repo Signed-off-by: Adam Dabrowski --- posts/rep-0158:2006.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/posts/rep-0158:2006.md b/posts/rep-0158:2006.md index 83f49b2..d5cfff4 100644 --- a/posts/rep-0158:2006.md +++ b/posts/rep-0158:2006.md @@ -432,7 +432,7 @@ The standard introduced by this REP is a subject of automation through complianc ## Implementation -This REP is implemented through the core schema and the registry described in Section 4, as well as tools to be provided within `ros-simulation/openusd-schemas` repository: +This REP is implemented through the core schema and the registry described in Section 4, as well as compliance tools, all provided within [ros-simulation/openusd-schemas](https://github.com/ros-simulation/openusd-schemas) repository: ### Compliance Checker A REP compliance checker is to be developed and shared with the community. The tool will provide validation of all REP recommendations for OpenUSD assets and supply actionable feedback for the user for every violation or non-conformance. From bf0549f9695a4ce85ed15709bc0be4c0617dc4bf Mon Sep 17 00:00:00 2001 From: Adam Dabrowski Date: Thu, 7 May 2026 17:55:58 +0200 Subject: [PATCH 110/111] moved to correct _posts directory Signed-off-by: Adam Dabrowski --- {posts => _posts}/rep-0158:2006.md | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename {posts => _posts}/rep-0158:2006.md (100%) diff --git a/posts/rep-0158:2006.md b/_posts/rep-0158:2006.md similarity index 100% rename from posts/rep-0158:2006.md rename to _posts/rep-0158:2006.md From 159ca5a409126ee5202944f4a058ac18448c72ea Mon Sep 17 00:00:00 2001 From: Adam Dabrowski Date: Tue, 12 May 2026 13:59:15 +0200 Subject: [PATCH 111/111] PMC sponsor pending Signed-off-by: Adam Dabrowski --- _posts/rep-0158:2006.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/_posts/rep-0158:2006.md b/_posts/rep-0158:2006.md index d5cfff4..463381c 100644 --- a/_posts/rep-0158:2006.md +++ b/_posts/rep-0158:2006.md @@ -3,7 +3,7 @@ layout: post REP: 0158:2026 title: OpenUSD Conventions for Simulation Asset Interoperability authors: Adam Dabrowski, Mateusz Zak, Michal Pelka (Robotec.ai), Ayush Ghosh, Renato Gasoto (NVIDIA), Franco Cipollone (Ekumen) -PMC Sponsor: Michael Carroll +PMC Sponsor: Pending PMCs: ROS discussion: Pending tag: Draft