From 25afa5c6b25bc787a603dc66ee7c183138979d84 Mon Sep 17 00:00:00 2001 From: mgussert Date: Thu, 18 Sep 2025 17:32:08 -0700 Subject: [PATCH 1/4] fixing broken non api auto-doc links from comments in source --- docs/source/how-to/add_own_library.rst | 2 ++ docs/source/how-to/import_new_asset.rst | 4 ++-- docs/source/how-to/master_omniverse.rst | 1 - docs/source/overview/developer-guide/vs_code.rst | 3 +-- docs/source/overview/environments.rst | 2 +- docs/source/refs/contributing.rst | 7 ++----- docs/source/refs/license.rst | 3 ++- docs/source/refs/reference_architecture/index.rst | 15 ++++++++------- docs/source/refs/release_notes.rst | 4 ++-- .../setup/installation/binaries_installation.rst | 2 +- .../setup/installation/pip_installation.rst | 4 ++-- docs/source/tutorials/00_sim/launch_app.rst | 2 +- docs/source/tutorials/01_assets/add_new_robot.rst | 2 +- 13 files changed, 25 insertions(+), 26 deletions(-) diff --git a/docs/source/how-to/add_own_library.rst b/docs/source/how-to/add_own_library.rst index d0cb9dd5a62..e84578fca52 100644 --- a/docs/source/how-to/add_own_library.rst +++ b/docs/source/how-to/add_own_library.rst @@ -1,3 +1,5 @@ +.. _how-to-add-library: + Adding your own learning library ================================ diff --git a/docs/source/how-to/import_new_asset.rst b/docs/source/how-to/import_new_asset.rst index 9d2f828ad40..41eacc48673 100644 --- a/docs/source/how-to/import_new_asset.rst +++ b/docs/source/how-to/import_new_asset.rst @@ -307,8 +307,8 @@ of gravity. .. _instanceable: https://openusd.org/dev/api/_usd__page__scenegraph_instancing.html .. _documentation: https://docs.isaacsim.omniverse.nvidia.com/latest/isaac_lab_tutorials/tutorial_instanceable_assets.html -.. _MJCF importer: https://docs.isaacsim.omniverse.nvidia.com/latest/robot_setup/import_mjcf.html -.. _URDF importer: https://docs.isaacsim.omniverse.nvidia.com/latest/robot_setup/import_urdf.html +.. _MJCF importer: https://docs.isaacsim.omniverse.nvidia.com/latest/importer_exporter/ext_isaacsim_asset_importer_mjcf.html +.. _URDF importer: https://docs.isaacsim.omniverse.nvidia.com/latest/importer_exporter/ext_isaacsim_asset_importer_urdf.html .. _anymal.urdf: https://github.com/isaac-orbit/anymal_d_simple_description/blob/master/urdf/anymal.urdf .. _asset converter: https://docs.omniverse.nvidia.com/extensions/latest/ext_asset-converter.html .. _mujoco_menagerie: https://github.com/google-deepmind/mujoco_menagerie/tree/main/unitree_h1 diff --git a/docs/source/how-to/master_omniverse.rst b/docs/source/how-to/master_omniverse.rst index 0108ab64821..7360e8798cb 100644 --- a/docs/source/how-to/master_omniverse.rst +++ b/docs/source/how-to/master_omniverse.rst @@ -119,6 +119,5 @@ Part 3: More Resources - `Omniverse Glossary of Terms `__ - `Omniverse Code Samples `__ -- `PhysX Collider Compatibility `__ - `PhysX Limitations `__ - `PhysX Documentation `__. diff --git a/docs/source/overview/developer-guide/vs_code.rst b/docs/source/overview/developer-guide/vs_code.rst index f9ea07b6da3..e0c0040cffa 100644 --- a/docs/source/overview/developer-guide/vs_code.rst +++ b/docs/source/overview/developer-guide/vs_code.rst @@ -52,8 +52,7 @@ If everything executes correctly, it should create the following files: For more information on VSCode support for Omniverse, please refer to the following links: -* `Isaac Sim VSCode support `__ -* `Debugging with VSCode `__ +* `Isaac Sim VSCode support `__ Configuring the python interpreter diff --git a/docs/source/overview/environments.rst b/docs/source/overview/environments.rst index 7e3e2668e7b..b29f90972ea 100644 --- a/docs/source/overview/environments.rst +++ b/docs/source/overview/environments.rst @@ -375,7 +375,7 @@ Environments based on legged locomotion tasks. .. |velocity-flat-digit-link| replace:: `Isaac-Velocity-Flat-Digit-v0 `__ .. |velocity-rough-digit-link| replace:: `Isaac-Velocity-Rough-Digit-v0 `__ -.. |tracking-loco-manip-digit-link| replace:: `Isaac-Tracking-Flat-Digit-v0 `__ +.. |tracking-loco-manip-digit-link| replace:: `Isaac-Tracking-Flat-Digit-v0 `__ .. |velocity-flat-anymal-b| image:: ../_static/tasks/locomotion/anymal_b_flat.jpg .. |velocity-rough-anymal-b| image:: ../_static/tasks/locomotion/anymal_b_rough.jpg diff --git a/docs/source/refs/contributing.rst b/docs/source/refs/contributing.rst index f4bc45003b7..85721ff0f49 100644 --- a/docs/source/refs/contributing.rst +++ b/docs/source/refs/contributing.rst @@ -112,11 +112,8 @@ integrated with the `NVIDIA Omniverse Platform `__. -To use this content, you can use the Asset Browser provided in Isaac Sim. - -Please check the `Isaac Sim documentation `__ -for more information on how to download the assets. +Please checkout the `Isaac Sim Assets `__ +for more information on what is presently available. .. attention:: diff --git a/docs/source/refs/license.rst b/docs/source/refs/license.rst index 4d907efa15e..fa4bb221f5d 100644 --- a/docs/source/refs/license.rst +++ b/docs/source/refs/license.rst @@ -5,7 +5,8 @@ License NVIDIA Isaac Sim is available freely under `individual license `_. For more information -about its license terms, please check `here `_. +about its license terms, please check `here `_ +and `here `_ . The license files for all its dependencies and included assets are available in its `documentation `_. diff --git a/docs/source/refs/reference_architecture/index.rst b/docs/source/refs/reference_architecture/index.rst index 34296144506..6aad8b4156e 100644 --- a/docs/source/refs/reference_architecture/index.rst +++ b/docs/source/refs/reference_architecture/index.rst @@ -195,10 +195,12 @@ Some wrappers include: * `Video Wrappers `__ * `RL Libraries Wrappers `__ +.. currentmodule:: isaaclab_rl + Most RL libraries expect their own variation of an environment interface. This means the data types needed by each library differs. Isaac Lab provides its own wrappers to convert the environment into the expected interface by the RL library a user wants to use. These are -specified in the `Isaac Lab utils wrapper module `__. +specified in :class:`isaaclab_rl` See the `full list `__ of other wrappers APIs. For more information on how these wrappers work, please refer to the `Wrapping environments `__ documentation. @@ -345,7 +347,7 @@ Check out our resources on using Isaac Lab with your robots. Review Our Documentation & Samples Resources -* `Isaac Lab Tutorials`_ +* :ref:`Isaac Lab Tutorials ` * `Fast-Track Robot Learning in Simulation Using NVIDIA Isaac Lab`_ * `Supercharge Robotics Workflows with AI and Simulation Using NVIDIA Isaac Sim 4.0 and NVIDIA Isaac Lab`_ * `Closing the Sim-to-Real Gap: Training Spot Quadruped Locomotion with NVIDIA Isaac Lab `__ @@ -360,16 +362,15 @@ Learn More About Featured NVIDIA Solutions .. _curriculum learning: https://arxiv.org/abs/2109.11978 .. _CAD Converter: https://docs.omniverse.nvidia.com/extensions/latest/ext_cad-converter.html -.. _URDF Importer: https://docs.isaacsim.omniverse.nvidia.com/latest/robot_setup/ext_isaacsim_asset_importer_urdf.html -.. _MJCF Importer: https://docs.isaacsim.omniverse.nvidia.com/latest/robot_setup/ext_isaacsim_asset_importer_mjcf.html +.. _URDF Importer: https://docs.isaacsim.omniverse.nvidia.com/latest/importer_exporter/ext_isaacsim_asset_importer_urdf.html +.. _MJCF Importer: https://docs.isaacsim.omniverse.nvidia.com/latest/importer_exporter/ext_isaacsim_asset_importer_mjcf.html .. _Onshape Importer: https://docs.omniverse.nvidia.com/extensions/latest/ext_onshape.html -.. _Isaac Sim Reference Architecture: https://docs.isaacsim.omniverse.nvidia.com/latest/isaac_sim_reference_architecture.html -.. _Importing Assets section: https://docs.isaacsim.omniverse.nvidia.com/latest/isaac_sim_reference_architecture.html#importing-assets +.. _Isaac Sim Reference Architecture: https://docs.isaacsim.omniverse.nvidia.com/latest/introduction/reference_architecture.html +.. _Importing Assets section: https://docs.isaacsim.omniverse.nvidia.com/latest/importer_exporter/importers_exporters.html .. _Scale AI-Enabled Robotics Development Workloads with NVIDIA OSMO: https://developer.nvidia.com/blog/scale-ai-enabled-robotics-development-workloads-with-nvidia-osmo/ .. _Isaac Perceptor: https://developer.nvidia.com/isaac/perceptor .. _Isaac Manipulator: https://developer.nvidia.com/isaac/manipulator .. _Additional Resources: https://isaac-sim.github.io/IsaacLab/main/source/refs/additional_resources.html -.. _Isaac Lab Tutorials: file:///home/oomotuyi/isaac/IsaacLab/docs/_build/current/source/tutorials/index.html .. _Fast-Track Robot Learning in Simulation Using NVIDIA Isaac Lab: https://developer.nvidia.com/blog/fast-track-robot-learning-in-simulation-using-nvidia-isaac-lab/ .. _Supercharge Robotics Workflows with AI and Simulation Using NVIDIA Isaac Sim 4.0 and NVIDIA Isaac Lab: https://developer.nvidia.com/blog/supercharge-robotics-workflows-with-ai-and-simulation-using-nvidia-isaac-sim-4-0-and-nvidia-isaac-lab/ diff --git a/docs/source/refs/release_notes.rst b/docs/source/refs/release_notes.rst index 59396ce33ef..3542770f9bd 100644 --- a/docs/source/refs/release_notes.rst +++ b/docs/source/refs/release_notes.rst @@ -1270,12 +1270,12 @@ New Features * Integrated CI/CD pipeline, which is triggered on pull requests and publishes the results publicly * Extended support for Windows OS platforms -* Added `tiled rendered `_ based Camera +* Added tiled render based Camera sensor implementation. This provides optimized RGB-D rendering throughputs of up to 10k frames per second. * Added support for multi-GPU and multi-node training for the RL-Games library * Integrated APIs for environment designing (direct workflow) without relying on managers * Added implementation of delayed PD actuator model -* `Added various new learning environments `_: +* Added various new learning environments: * Cartpole balancing using images * Shadow hand cube reorientation * Boston Dynamics Spot locomotion diff --git a/docs/source/setup/installation/binaries_installation.rst b/docs/source/setup/installation/binaries_installation.rst index d066f7ce0b0..53ad5ac49fe 100644 --- a/docs/source/setup/installation/binaries_installation.rst +++ b/docs/source/setup/installation/binaries_installation.rst @@ -152,7 +152,7 @@ instructions, it means that something is incorrectly configured. To debug and troubleshoot, please check Isaac Sim `documentation `__ and the -`forums `__. +`forums `__. Installing Isaac Lab diff --git a/docs/source/setup/installation/pip_installation.rst b/docs/source/setup/installation/pip_installation.rst index 11fedf6afcd..31c05ec2c08 100644 --- a/docs/source/setup/installation/pip_installation.rst +++ b/docs/source/setup/installation/pip_installation.rst @@ -11,7 +11,7 @@ Installing Isaac Sim From Isaac Sim 4.0 release, it is possible to install Isaac Sim using pip. This approach makes it easier to install Isaac Sim without requiring to download the Isaac Sim binaries. If you encounter any issues, please report them to the -`Isaac Sim Forums `_. +`Isaac Sim Forums `_. .. attention:: @@ -382,7 +382,7 @@ We recommend adding ``--headless`` for faster training. isaaclab.bat -p scripts/reinforcement_learning/rsl_rl/train.py --task=Isaac-Velocity-Rough-Anymal-C-v0 --headless -Isaac Lab provides the tools you'll need to create your own **Tasks** and **Workflows** for whatever your project needs may be. Take a look at our :ref:`how-to` guides like `Adding your own learning Library `_ or `Wrapping Environments `_ for details. +Isaac Lab provides the tools you'll need to create your own **Tasks** and **Workflows** for whatever your project needs may be. Take a look at our :ref:`how-to` guides like :ref:`adding your own RL library ` or :ref:`wrapping environments ` for details. .. figure:: ../../_static/setup/isaac_ants_example.jpg :align: center diff --git a/docs/source/tutorials/00_sim/launch_app.rst b/docs/source/tutorials/00_sim/launch_app.rst index 8013e9975c3..05fa32c4648 100644 --- a/docs/source/tutorials/00_sim/launch_app.rst +++ b/docs/source/tutorials/00_sim/launch_app.rst @@ -172,5 +172,5 @@ want our simulation to be more performant. The process can be killed by pressing terminal. -.. _specification: https://docs.omniverse.nvidia.com/py/isaacsim/source/isaacsim.simulation_app/docs/index.html#isaacsim.simulation_app.SimulationApp.DEFAULT_LAUNCHER_CONFIG +.. _specification: https://docs.isaacsim.omniverse.nvidia.com/latest/py/source/extensions/isaacsim.simulation_app/docs/index.html#isaacsim.simulation_app.SimulationApp.DEFAULT_LAUNCHER_CONFIG .. _WebRTC Livestreaming: https://docs.isaacsim.omniverse.nvidia.com/latest/installation/manual_livestream_clients.html#isaac-sim-short-webrtc-streaming-client diff --git a/docs/source/tutorials/01_assets/add_new_robot.rst b/docs/source/tutorials/01_assets/add_new_robot.rst index 61664cef518..a4d258f82c1 100644 --- a/docs/source/tutorials/01_assets/add_new_robot.rst +++ b/docs/source/tutorials/01_assets/add_new_robot.rst @@ -6,7 +6,7 @@ Adding a New Robot to Isaac Lab .. currentmodule:: isaaclab Simulating and training a new robot is a multi-step process that starts with importing the robot into Isaac Sim. -This is covered in depth in the Isaac Sim documentation `here `_. +This is covered in depth in the Isaac Sim documentation `here `_. Once the robot is imported and tuned for simulation, we must define those interfaces necessary to clone the robot across multiple environments, drive its joints, and properly reset it, regardless of the chosen workflow or training framework. From 79124cf7d5451a38c3768eaad56a846cccbc87e1 Mon Sep 17 00:00:00 2001 From: mgussert Date: Thu, 18 Sep 2025 20:01:40 -0700 Subject: [PATCH 2/4] fixed api autodoc links. removed a lot of explicit references to physX 5 --- source/isaaclab/isaaclab/app/app_launcher.py | 2 +- source/isaaclab/isaaclab/envs/__init__.py | 2 +- source/isaaclab/isaaclab/scene/interactive_scene.py | 2 +- .../isaaclab/sensors/contact_sensor/contact_sensor.py | 2 +- .../isaaclab/sensors/ray_caster/patterns/patterns.py | 2 +- source/isaaclab/isaaclab/sim/converters/mesh_converter.py | 2 +- source/isaaclab/isaaclab/sim/simulation_context.py | 2 +- .../isaaclab/isaaclab/sim/spawners/materials/__init__.py | 2 +- .../sim/spawners/materials/physics_materials_cfg.py | 7 ------- .../isaaclab/isaaclab/sim/spawners/sensors/sensors_cfg.py | 4 ---- source/isaaclab/isaaclab/sim/spawners/shapes/shapes.py | 2 +- source/isaaclab/isaaclab/sim/utils.py | 2 +- 12 files changed, 10 insertions(+), 21 deletions(-) diff --git a/source/isaaclab/isaaclab/app/app_launcher.py b/source/isaaclab/isaaclab/app/app_launcher.py index aa97e2bc3ec..1ecfbdd8642 100644 --- a/source/isaaclab/isaaclab/app/app_launcher.py +++ b/source/isaaclab/isaaclab/app/app_launcher.py @@ -76,7 +76,7 @@ def __init__(self, launcher_args: argparse.Namespace | dict | None = None, **kwa such as ``LIVESTREAM``. .. _argparse.Namespace: https://docs.python.org/3/library/argparse.html?highlight=namespace#argparse.Namespace - .. _SimulationApp: https://docs.omniverse.nvidia.com/py/isaacsim/source/isaacsim.simulation_app/docs/index.html + .. _SimulationApp: https://docs.isaacsim.omniverse.nvidia.com/latest/py/source/extensions/isaacsim.simulation_app/docs/index.html#isaacsim.simulation_app.SimulationApp """ # We allow users to pass either a dict or an argparse.Namespace into # __init__, anticipating that these will be all of the argparse arguments diff --git a/source/isaaclab/isaaclab/envs/__init__.py b/source/isaaclab/isaaclab/envs/__init__.py index e69aba9d25c..2d274b8adad 100644 --- a/source/isaaclab/isaaclab/envs/__init__.py +++ b/source/isaaclab/isaaclab/envs/__init__.py @@ -39,7 +39,7 @@ For more information about the workflow design patterns, see the `Task Design Workflows`_ section. -.. _`Task Design Workflows`: https://isaac-sim.github.io/IsaacLab/source/features/task_workflows.html +.. _`Task Design Workflows`: https://docs.isaacsim.omniverse.nvidia.com/latest/introduction/workflows.html """ from . import mdp, ui diff --git a/source/isaaclab/isaaclab/scene/interactive_scene.py b/source/isaaclab/isaaclab/scene/interactive_scene.py index 141024ecb76..0f7592d41da 100644 --- a/source/isaaclab/isaaclab/scene/interactive_scene.py +++ b/source/isaaclab/isaaclab/scene/interactive_scene.py @@ -421,7 +421,7 @@ def extras(self) -> dict[str, XFormPrim]: These are not reset or updated by the scene. They are mainly other prims that are not necessarily handled by the interactive scene, but are useful to be accessed by the user. - .. _XFormPrim: https://docs.omniverse.nvidia.com/py/isaacsim/source/isaacsim.core/docs/index.html#isaacsim.core.prims.XFormPrim + .. _XFormPrim: https://docs.isaacsim.omniverse.nvidia.com/latest/py/source/extensions/isaacsim.core.prims/docs/index.html#isaacsim.core.prims.XFormPrim """ return self._extras diff --git a/source/isaaclab/isaaclab/sensors/contact_sensor/contact_sensor.py b/source/isaaclab/isaaclab/sensors/contact_sensor/contact_sensor.py index ba2a019ef64..aed50d390f8 100644 --- a/source/isaaclab/isaaclab/sensors/contact_sensor/contact_sensor.py +++ b/source/isaaclab/isaaclab/sensors/contact_sensor/contact_sensor.py @@ -58,7 +58,7 @@ class ContactSensor(SensorBase): it against the object. .. _PhysX ContactReporter: https://docs.omniverse.nvidia.com/kit/docs/omni_usd_schema_physics/104.2/class_physx_schema_physx_contact_report_a_p_i.html - .. _RigidContact: https://docs.omniverse.nvidia.com/py/isaacsim/source/isaacsim.core/docs/index.html#isaacsim.core.prims.RigidContact + .. _RigidContact: https://docs.isaacsim.omniverse.nvidia.com/latest/py/source/extensions/isaacsim.core.api/docs/index.html#isaacsim.core.api.sensors.RigidContactView """ cfg: ContactSensorCfg diff --git a/source/isaaclab/isaaclab/sensors/ray_caster/patterns/patterns.py b/source/isaaclab/isaaclab/sensors/ray_caster/patterns/patterns.py index 1a09f8b626f..2a6a438d178 100644 --- a/source/isaaclab/isaaclab/sensors/ray_caster/patterns/patterns.py +++ b/source/isaaclab/isaaclab/sensors/ray_caster/patterns/patterns.py @@ -109,7 +109,7 @@ def bpearl_pattern(cfg: patterns_cfg.BpearlPatternCfg, device: str) -> tuple[tor The `Robosense RS-Bpearl`_ is a short-range LiDAR that has a 360 degrees x 90 degrees super wide field of view. It is designed for near-field blind-spots detection. - .. _Robosense RS-Bpearl: https://www.roscomponents.com/en/lidar-laser-scanner/267-rs-bpearl.html + .. _Robosense RS-Bpearl: https://www.roscomponents.com/product/rs-bpearl/ Args: cfg: The configuration instance for the pattern. diff --git a/source/isaaclab/isaaclab/sim/converters/mesh_converter.py b/source/isaaclab/isaaclab/sim/converters/mesh_converter.py index 45502e73351..08be8fe2130 100644 --- a/source/isaaclab/isaaclab/sim/converters/mesh_converter.py +++ b/source/isaaclab/isaaclab/sim/converters/mesh_converter.py @@ -29,7 +29,7 @@ class MeshConverter(AssetConverterBase): instancing and physics work. The rigid body component must be added to each instance and not the referenced asset (i.e. the prototype prim itself). This is because the rigid body component defines properties that are specific to each instance and cannot be shared under the referenced asset. For - more information, please check the `documentation `_. + more information, please check the `documentation `_. Due to the above, we follow the following structure: diff --git a/source/isaaclab/isaaclab/sim/simulation_context.py b/source/isaaclab/isaaclab/sim/simulation_context.py index fd23d73c01c..fbd7f0043e9 100644 --- a/source/isaaclab/isaaclab/sim/simulation_context.py +++ b/source/isaaclab/isaaclab/sim/simulation_context.py @@ -783,7 +783,7 @@ def _set_additional_physx_params(self): # create the default physics material # this material is used when no material is specified for a primitive - # check: https://docs.omniverse.nvidia.com/extensions/latest/ext_physics/simulation-control/physics-settings.html#physics-materials + # check: https://isaac-sim.github.io/IsaacLab/main/source/api/lab/isaaclab.sim.html#isaaclab.sim.SimulationCfg.physics_material material_path = f"{self.cfg.physics_prim_path}/defaultMaterial" self.cfg.physics_material.func(material_path, self.cfg.physics_material) # bind the physics material to the scene diff --git a/source/isaaclab/isaaclab/sim/spawners/materials/__init__.py b/source/isaaclab/isaaclab/sim/spawners/materials/__init__.py index 052a2be4f88..966efec76b8 100644 --- a/source/isaaclab/isaaclab/sim/spawners/materials/__init__.py +++ b/source/isaaclab/isaaclab/sim/spawners/materials/__init__.py @@ -49,7 +49,7 @@ .. _Material Definition Language (MDL): https://raytracing-docs.nvidia.com/mdl/introduction/index.html#mdl_introduction# .. _Materials: https://docs.omniverse.nvidia.com/materials-and-rendering/latest/materials.html -.. _physics material: https://docs.omniverse.nvidia.com/extensions/latest/ext_physics/simulation-control/physics-settings.html#physics-materials +.. _physics material: https://isaac-sim.github.io/IsaacLab/main/source/api/lab/isaaclab.sim.html#isaaclab.sim.SimulationCfg.physics_material .. _USD Material Binding API: https://openusd.org/dev/api/class_usd_shade_material_binding_a_p_i.html .. _Physics Scene: https://openusd.org/dev/api/usd_physics_page_front.html """ diff --git a/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials_cfg.py b/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials_cfg.py index 8b6e6a30b2d..81351305ab7 100644 --- a/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials_cfg.py +++ b/source/isaaclab/isaaclab/sim/spawners/materials/physics_materials_cfg.py @@ -31,10 +31,6 @@ class RigidBodyMaterialCfg(PhysicsMaterialCfg): """Physics material parameters for rigid bodies. See :meth:`spawn_rigid_body_material` for more information. - - Note: - The default values are the `default values used by PhysX 5 - `__. """ func: Callable = physics_materials.spawn_rigid_body_material @@ -89,9 +85,6 @@ class DeformableBodyMaterialCfg(PhysicsMaterialCfg): See :meth:`spawn_deformable_body_material` for more information. - Note: - The default values are the `default values used by PhysX 5 - `__. """ func: Callable = physics_materials.spawn_deformable_body_material diff --git a/source/isaaclab/isaaclab/sim/spawners/sensors/sensors_cfg.py b/source/isaaclab/isaaclab/sim/spawners/sensors/sensors_cfg.py index 2f90030ab3d..70206d4839f 100644 --- a/source/isaaclab/isaaclab/sim/spawners/sensors/sensors_cfg.py +++ b/source/isaaclab/isaaclab/sim/spawners/sensors/sensors_cfg.py @@ -24,10 +24,6 @@ class PinholeCameraCfg(SpawnerCfg): ..note :: Focal length as well as the aperture sizes and offsets are set as a tenth of the world unit. In our case, the world unit is Meter s.t. all of these values are set in cm. - - .. note:: - The default values are taken from the `Replicator camera `__ - function. """ func: Callable = sensors.spawn_camera diff --git a/source/isaaclab/isaaclab/sim/spawners/shapes/shapes.py b/source/isaaclab/isaaclab/sim/spawners/shapes/shapes.py index 9b75664c878..f4fa156704a 100644 --- a/source/isaaclab/isaaclab/sim/spawners/shapes/shapes.py +++ b/source/isaaclab/isaaclab/sim/spawners/shapes/shapes.py @@ -244,7 +244,7 @@ def _spawn_geom_from_prim_type( instancing and physics work. The rigid body component must be added to each instance and not the referenced asset (i.e. the prototype prim itself). This is because the rigid body component defines properties that are specific to each instance and cannot be shared under the referenced asset. For - more information, please check the `documentation `_. + more information, please check the `documentation `_. Due to the above, we follow the following structure: diff --git a/source/isaaclab/isaaclab/sim/utils.py b/source/isaaclab/isaaclab/sim/utils.py index fa38bc18658..5a81aa7fee4 100644 --- a/source/isaaclab/isaaclab/sim/utils.py +++ b/source/isaaclab/isaaclab/sim/utils.py @@ -396,7 +396,7 @@ def bind_physics_material( The function is decorated with :meth:`apply_nested` to allow applying the function to a prim path and all its descendants. - .. _Physics material: https://docs.omniverse.nvidia.com/extensions/latest/ext_physics/simulation-control/physics-settings.html#physics-materials + .. _Physics material: https://isaac-sim.github.io/IsaacLab/main/source/api/lab/isaaclab.sim.html#isaaclab.sim.SimulationCfg.physics_material Args: prim_path: The prim path where to apply the material. From 41adeec221f26e7846e884b71353228134c57cc6 Mon Sep 17 00:00:00 2001 From: mgussert Date: Thu, 18 Sep 2025 20:08:05 -0700 Subject: [PATCH 3/4] format... --- docs/source/refs/license.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/source/refs/license.rst b/docs/source/refs/license.rst index fa4bb221f5d..a0c04c5cf6a 100644 --- a/docs/source/refs/license.rst +++ b/docs/source/refs/license.rst @@ -5,7 +5,7 @@ License NVIDIA Isaac Sim is available freely under `individual license `_. For more information -about its license terms, please check `here `_ +about its license terms, please check `here `_ and `here `_ . The license files for all its dependencies and included assets are available in its `documentation `_. From 9bdc58f27b7135b26ec8db572a30ac8c5cb84d76 Mon Sep 17 00:00:00 2001 From: mgussert Date: Thu, 18 Sep 2025 20:27:20 -0700 Subject: [PATCH 4/4] missed one... --- .../setup/installation/pip_installation.rst | 225 ------------------ 1 file changed, 225 deletions(-) diff --git a/docs/source/setup/installation/pip_installation.rst b/docs/source/setup/installation/pip_installation.rst index 54131b17118..3e718f78349 100644 --- a/docs/source/setup/installation/pip_installation.rst +++ b/docs/source/setup/installation/pip_installation.rst @@ -63,229 +63,4 @@ Installing Isaac Lab .. include:: include/src_build_isaaclab.rst -<<<<<<< HEAD - We recommend making a `fork `_ of the Isaac Lab repository to contribute - to the project but this is not mandatory to use the framework. If you - make a fork, please replace ``isaac-sim`` with your username - in the following instructions. - -Clone the Isaac Lab repository into your workspace: - -.. tab-set:: - - .. tab-item:: SSH - - .. code:: bash - - git clone git@github.com:isaac-sim/IsaacLab.git - - .. tab-item:: HTTPS - - .. code:: bash - - git clone https://github.com/isaac-sim/IsaacLab.git - - -.. note:: - We provide a helper executable `isaaclab.sh `_ that provides - utilities to manage extensions: - - .. tab-set:: - :sync-group: os - - .. tab-item:: :icon:`fa-brands fa-linux` Linux - :sync: linux - - .. code:: text - - ./isaaclab.sh --help - - usage: isaaclab.sh [-h] [-i] [-f] [-p] [-s] [-t] [-o] [-v] [-d] [-n] [-c] -- Utility to manage Isaac Lab. - - optional arguments: - -h, --help Display the help content. - -i, --install [LIB] Install the extensions inside Isaac Lab and learning frameworks (rl_games, rsl_rl, sb3, skrl) as extra dependencies. Default is 'all'. - -f, --format Run pre-commit to format the code and check lints. - -p, --python Run the python executable provided by Isaac Sim or virtual environment (if active). - -s, --sim Run the simulator executable (isaac-sim.sh) provided by Isaac Sim. - -t, --test Run all python pytest tests. - -o, --docker Run the docker container helper script (docker/container.sh). - -v, --vscode Generate the VSCode settings file from template. - -d, --docs Build the documentation from source using sphinx. - -n, --new Create a new external project or internal task from template. - -c, --conda [NAME] Create the conda environment for Isaac Lab. Default name is 'env_isaaclab'. - - .. tab-item:: :icon:`fa-brands fa-windows` Windows - :sync: windows - - .. code:: text - - isaaclab.bat --help - - usage: isaaclab.bat [-h] [-i] [-f] [-p] [-s] [-v] [-d] [-n] [-c] -- Utility to manage Isaac Lab. - - optional arguments: - -h, --help Display the help content. - -i, --install [LIB] Install the extensions inside Isaac Lab and learning frameworks (rl_games, rsl_rl, sb3, skrl) as extra dependencies. Default is 'all'. - -f, --format Run pre-commit to format the code and check lints. - -p, --python Run the python executable provided by Isaac Sim or virtual environment (if active). - -s, --sim Run the simulator executable (isaac-sim.bat) provided by Isaac Sim. - -t, --test Run all python pytest tests. - -v, --vscode Generate the VSCode settings file from template. - -d, --docs Build the documentation from source using sphinx. - -n, --new Create a new external project or internal task from template. - -c, --conda [NAME] Create the conda environment for Isaac Lab. Default name is 'env_isaaclab'. - -Installation -~~~~~~~~~~~~ - -- Install dependencies using ``apt`` (on Ubuntu): - - .. code:: bash - - sudo apt install cmake build-essential - -- Run the install command that iterates over all the extensions in ``source`` directory and installs them - using pip (with ``--editable`` flag): - -.. tab-set:: - :sync-group: os - - .. tab-item:: :icon:`fa-brands fa-linux` Linux - :sync: linux - - .. code:: bash - - ./isaaclab.sh --install # or "./isaaclab.sh -i" - - .. tab-item:: :icon:`fa-brands fa-windows` Windows - :sync: windows - - .. code:: bash - - isaaclab.bat --install :: or "isaaclab.bat -i" - -.. note:: - - By default, this will install all the learning frameworks. If you want to install only a specific framework, you can - pass the name of the framework as an argument. For example, to install only the ``rl_games`` framework, you can run - - .. tab-set:: - :sync-group: os - - .. tab-item:: :icon:`fa-brands fa-linux` Linux - :sync: linux - - .. code:: bash - - ./isaaclab.sh --install rl_games # or "./isaaclab.sh -i rl_games" - - .. tab-item:: :icon:`fa-brands fa-windows` Windows - :sync: windows - - .. code:: bash - - isaaclab.bat --install rl_games :: or "isaaclab.bat -i rl_games" - - The valid options are ``rl_games``, ``rsl_rl``, ``sb3``, ``skrl``, ``robomimic``, ``none``. - - -Verifying the Isaac Lab installation -~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ - -To verify that the installation was successful, run the following command from the -top of the repository: - -.. tab-set:: - :sync-group: os - - .. tab-item:: :icon:`fa-brands fa-linux` Linux - :sync: linux - - .. code:: bash - - # Option 1: Using the isaaclab.sh executable - # note: this works for both the bundled python and the virtual environment - ./isaaclab.sh -p scripts/tutorials/00_sim/create_empty.py - - # Option 2: Using python in your virtual environment - python scripts/tutorials/00_sim/create_empty.py - - .. tab-item:: :icon:`fa-brands fa-windows` Windows - :sync: windows - - .. code:: batch - - :: Option 1: Using the isaaclab.bat executable - :: note: this works for both the bundled python and the virtual environment - isaaclab.bat -p scripts\tutorials\00_sim\create_empty.py - - :: Option 2: Using python in your virtual environment - python scripts\tutorials\00_sim\create_empty.py - - -The above command should launch the simulator and display a window with a black -viewport as shown below. You can exit the script by pressing ``Ctrl+C`` on your terminal. -On Windows machines, please terminate the process from Command Prompt using -``Ctrl+Break`` or ``Ctrl+fn+B``. - - -.. figure:: ../../_static/setup/verify_install.jpg - :align: center - :figwidth: 100% - :alt: Simulator with a black window. - - -If you see this, then the installation was successful! |:tada:| - -Train a robot! -~~~~~~~~~~~~~~~ - -You can now use Isaac Lab to train a robot through Reinforcement Learning! The quickest way to use Isaac Lab is through the predefined workflows using one of our **Batteries-included** robot tasks. Execute the following command to quickly train an ant to walk! -We recommend adding ``--headless`` for faster training. - -.. tab-set:: - :sync-group: os - - .. tab-item:: :icon:`fa-brands fa-linux` Linux - :sync: linux - - .. code:: bash - - ./isaaclab.sh -p scripts/reinforcement_learning/rsl_rl/train.py --task=Isaac-Ant-v0 --headless - - .. tab-item:: :icon:`fa-brands fa-windows` Windows - :sync: windows - - .. code:: batch - - isaaclab.bat -p scripts/reinforcement_learning/rsl_rl/train.py --task=Isaac-Ant-v0 --headless - -... Or a robot dog! - -.. tab-set:: - :sync-group: os - - .. tab-item:: :icon:`fa-brands fa-linux` Linux - :sync: linux - - .. code:: bash - - ./isaaclab.sh -p scripts/reinforcement_learning/rsl_rl/train.py --task=Isaac-Velocity-Rough-Anymal-C-v0 --headless - - .. tab-item:: :icon:`fa-brands fa-windows` Windows - :sync: windows - - .. code:: batch - - isaaclab.bat -p scripts/reinforcement_learning/rsl_rl/train.py --task=Isaac-Velocity-Rough-Anymal-C-v0 --headless - -Isaac Lab provides the tools you'll need to create your own **Tasks** and **Workflows** for whatever your project needs may be. Take a look at our :ref:`how-to` guides like :ref:`adding your own RL library ` or :ref:`wrapping environments ` for details. - -.. figure:: ../../_static/setup/isaac_ants_example.jpg - :align: center - :figwidth: 100% - :alt: Idle hands... -======= .. include:: include/src_verify_isaaclab.rst ->>>>>>> main