Skip to content

Commit

Permalink
Merge branch 'main' into main
Browse files Browse the repository at this point in the history
Signed-off-by: Hongyu Li <[email protected]>
  • Loading branch information
lhy0807 authored Dec 18, 2024
2 parents 7a5ce12 + 874b7b6 commit da0a686
Show file tree
Hide file tree
Showing 146 changed files with 9,279 additions and 712 deletions.
2 changes: 1 addition & 1 deletion .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ repos:
- id: pyupgrade
args: ["--py310-plus"]
# FIXME: This is a hack because Pytorch does not like: torch.Tensor | dict aliasing
exclude: "source/extensions/omni.isaac.lab/omni/isaac/lab/envs/common.py"
exclude: "source/extensions/omni.isaac.lab/omni/isaac/lab/envs/common.py|source/extensions/omni.isaac.lab/omni/isaac/lab/ui/widgets/image_plot.py"
- repo: https://github.com/codespell-project/codespell
rev: v2.2.6
hooks:
Expand Down
3 changes: 3 additions & 0 deletions CONTRIBUTORS.md
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@ Guidelines for modifications:
* HoJin Jeon
* Hongwei Xiong
* Hongyu Li
* Iretiayo Akinola
* Jan Kerner
* Jean Tampon
* Jia Lin Yuan
Expand All @@ -64,6 +65,7 @@ Guidelines for modifications:
* Lorenz Wellhausen
* Masoud Moghani
* Michael Gussert
* Michael Noseworthy
* Muhong Guo
* Nuralem Abizov
* Oyindamola Omotuyi
Expand Down Expand Up @@ -92,3 +94,4 @@ Guidelines for modifications:
* Gavriel State
* Hammad Mazhar
* Marco Hutter
* Yashraj Narang
Binary file added docs/source/_static/tasks/factory/gear_mesh.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added docs/source/_static/tasks/factory/nut_thread.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added docs/source/_static/tasks/factory/peg_insert.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
16 changes: 16 additions & 0 deletions docs/source/api/lab/omni.isaac.lab.controllers.rst
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,8 @@

DifferentialIKController
DifferentialIKControllerCfg
OperationalSpaceController
OperationalSpaceControllerCfg

Differential Inverse Kinematics
-------------------------------
Expand All @@ -23,3 +25,17 @@ Differential Inverse Kinematics
:inherited-members:
:show-inheritance:
:exclude-members: __init__, class_type

Operational Space controllers
-----------------------------

.. autoclass:: OperationalSpaceController
:members:
:inherited-members:
:show-inheritance:

.. autoclass:: OperationalSpaceControllerCfg
:members:
:inherited-members:
:show-inheritance:
:exclude-members: __init__, class_type
4 changes: 2 additions & 2 deletions docs/source/migration/migrating_from_isaacgymenvs.rst
Original file line number Diff line number Diff line change
Expand Up @@ -814,9 +814,9 @@ The ``progress_buf`` variable has also been renamed to ``episode_length_buf``.
| | |
| | self.joint_pos[env_ids] = joint_pos |
| | |
| | self.cartpole.write_root_pose_to_sim( |
| | self.cartpole.write_root_link_pose_to_sim( |
| | default_root_state[:, :7], env_ids) |
| | self.cartpole.write_root_velocity_to_sim( |
| | self.cartpole.write_root_com_velocity_to_sim( |
| | default_root_state[:, 7:], env_ids) |
| | self.cartpole.write_joint_state_to_sim( |
| | joint_pos, joint_vel, None, env_ids) |
Expand Down
8 changes: 4 additions & 4 deletions docs/source/migration/migrating_from_omniisaacgymenvs.rst
Original file line number Diff line number Diff line change
Expand Up @@ -364,8 +364,8 @@ In Isaac Lab, ``root_pose`` and ``root_velocity`` have been combined into single

.. code-block::python
self.cartpole.write_root_pose_to_sim(default_root_state[:, :7], env_ids)
self.cartpole.write_root_velocity_to_sim(default_root_state[:, 7:], env_ids)
self.cartpole.write_root_link_pose_to_sim(default_root_state[:, :7], env_ids)
self.cartpole.write_root_com_velocity_to_sim(default_root_state[:, 7:], env_ids)
Creating a New Environment
Expand Down Expand Up @@ -738,9 +738,9 @@ reset the ``episode_length_buf`` buffer.
| 1.0 - 2.0 * torch.rand(num_resets, device=self._device)) | self.joint_pos[env_ids] = joint_pos |
| | self.joint_vel[env_ids] = joint_vel |
| # apply resets | |
| indices = env_ids.to(dtype=torch.int32) | self.cartpole.write_root_pose_to_sim( |
| indices = env_ids.to(dtype=torch.int32) | self.cartpole.write_root_link_pose_to_sim( |
| self._cartpoles.set_joint_positions(dof_pos, indices=indices) | default_root_state[:, :7], env_ids) |
| self._cartpoles.set_joint_velocities(dof_vel, indices=indices) | self.cartpole.write_root_velocity_to_sim( |
| self._cartpoles.set_joint_velocities(dof_vel, indices=indices) | self.cartpole.write_root_com_velocity_to_sim( |
| | default_root_state[:, 7:], env_ids) |
| # bookkeeping | self.cartpole.write_joint_state_to_sim( |
| self.reset_buf[env_ids] = 0 | joint_pos, joint_vel, None, env_ids) |
Expand Down
53 changes: 51 additions & 2 deletions docs/source/overview/environments.rst
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ Manipulation
Environments based on fixed-arm manipulation tasks.

For many of these tasks, we include configurations with different arm action spaces. For example,
for the reach environment:
for the lift-cube environment:

* |lift-cube-link|: Franka arm with joint position control
* |lift-cube-ik-abs-link|: Franka arm with absolute IK control
Expand Down Expand Up @@ -134,7 +134,7 @@ for the reach environment:
.. |cabi-franka| image:: ../_static/tasks/manipulation/franka_open_drawer.jpg
.. |cube-allegro| image:: ../_static/tasks/manipulation/allegro_cube.jpg
.. |cube-shadow| image:: ../_static/tasks/manipulation/shadow_cube.jpg
.. |stack-franka| image:: ../_static/tasks/manipulation/franka_stack.jpg
.. |stack-cube| image:: ../_static/tasks/manipulation/franka_stack.jpg

.. |reach-franka-link| replace:: `Isaac-Reach-Franka-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/manipulation/reach/config/franka/joint_pos_env_cfg.py>`__
.. |reach-ur10-link| replace:: `Isaac-Reach-UR10-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/manager_based/manipulation/reach/config/ur_10/joint_pos_env_cfg.py>`__
Expand All @@ -152,6 +152,39 @@ for the reach environment:
.. |cube-shadow-lstm-link| replace:: `Isaac-Repose-Cube-Shadow-OpenAI-LSTM-Direct-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/direct/shadow_hand/shadow_hand_env_cfg.py>`__
.. |cube-shadow-vis-link| replace:: `Isaac-Repose-Cube-Shadow-Vision-Direct-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/direct/shadow_hand/shadow_hand_vision_env.py>`__

Contact-rich Manipulation
~~~~~~~~~~~~

Environments based on contact-rich manipulation tasks such as peg insertion, gear meshing and nut-bolt fastening.

These tasks share the same task configurations and control options. You can switch between them by specifying the task name.
For example:

* |factory-peg-link|: Peg insertion with the Franka arm
* |factory-gear-link|: Gear meshing with the Franka arm
* |factory-nut-link|: Nut-Bolt fastening with the Franka arm

.. table::
:widths: 33 37 30

+--------------------+-------------------------+-----------------------------------------------------------------------------+
| World | Environment ID | Description |
+====================+=========================+=============================================================================+
| |factory-peg| | |factory-peg-link| | Insert peg into the socket with the Franka robot |
+--------------------+-------------------------+-----------------------------------------------------------------------------+
| |factory-gear| | |factory-gear-link| | Insert and mesh gear into the base with other gears, using the Franka robot |
+--------------------+-------------------------+-----------------------------------------------------------------------------+
| |factory-nut| | |factory-nut-link| | Thread the nut onto the first 2 threads of the bolt, using the Franka robot |
+--------------------+-------------------------+-----------------------------------------------------------------------------+

.. |factory-peg| image:: ../_static/tasks/factory/peg_insert.jpg
.. |factory-gear| image:: ../_static/tasks/factory/gear_mesh.jpg
.. |factory-nut| image:: ../_static/tasks/factory/nut_thread.jpg

.. |factory-peg-link| replace:: `Isaac-Factory-PegInsert-Direct-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/direct/factory/factory_env_cfg.py>`__
.. |factory-gear-link| replace:: `Isaac-Factory-GearMesh-Direct-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/direct/factory/factory_env_cfg.py>`__
.. |factory-nut-link| replace:: `Isaac-Factory-NutThread-Direct-v0 <https://github.com/isaac-sim/IsaacLab/blob/main/source/extensions/omni.isaac.lab_tasks/omni/isaac/lab_tasks/direct/factory/factory_env_cfg.py>`__

Locomotion
~~~~~~~~~~

Expand Down Expand Up @@ -369,6 +402,18 @@ Comprehensive List of Environments
-
- Manager Based
- **rl_games** (PPO), **rsl_rl** (PPO), **skrl** (PPO), **sb3** (PPO)
* - Isaac-Factory-GearMesh-Direct-v0
-
- Direct
- **rl_games** (PPO)
* - Isaac-Factory-NutThread-Direct-v0
-
- Direct
- **rl_games** (PPO)
* - Isaac-Factory-PegInsert-Direct-v0
-
- Direct
- **rl_games** (PPO)
* - Isaac-Franka-Cabinet-Direct-v0
-
- Direct
Expand Down Expand Up @@ -421,6 +466,10 @@ Comprehensive List of Environments
-
- Manager Based
-
* - Isaac-Reach-Franka-OSC-v0
- Isaac-Reach-Franka-OSC-Play-v0
- Manager Based
- **rsl_rl** (PPO)
* - Isaac-Reach-Franka-v0
- Isaac-Reach-Franka-Play-v0
- Manager Based
Expand Down
1 change: 1 addition & 0 deletions docs/source/overview/sensors/ray_caster.rst
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@ Using a ray caster sensor requires a **pattern** and a parent xform to be attach
update_period = 1/60,
offset=RayCasterCfg.OffsetCfg(pos=(0,0,0.5)),
mesh_prim_paths=["/World/Ground"],
attach_yaw_only=True,
pattern_cfg=patterns.LidarPatternCfg(
channels = 100,
vertical_fov_range=[-90, 90],
Expand Down
4 changes: 2 additions & 2 deletions docs/source/tutorials/01_assets/run_articulation.rst
Original file line number Diff line number Diff line change
Expand Up @@ -66,8 +66,8 @@ Similar to a rigid object, an articulation also has a root state. This state cor
articulation tree. On top of the root state, an articulation also has joint states. These states correspond to the
joint positions and velocities.

To reset the articulation, we first set the root state by calling the :meth:`Articulation.write_root_state_to_sim`
method. Similarly, we set the joint states by calling the :meth:`Articulation.write_joint_state_to_sim` method.
To reset the articulation, we first set the root state by calling the :meth:`Articulation.write_root_link_pose_to_sim` and :meth:`Articulation.write_root_com_velocity_to_sim`
methods. Similarly, we set the joint states by calling the :meth:`Articulation.write_joint_state_to_sim` method.
Finally, we call the :meth:`Articulation.reset` method to reset any internal buffers and caches.

.. literalinclude:: ../../../../source/standalone/tutorials/01_assets/run_articulation.py
Expand Down
2 changes: 1 addition & 1 deletion docs/source/tutorials/01_assets/run_deformable_object.rst
Original file line number Diff line number Diff line change
Expand Up @@ -149,7 +149,7 @@ the average position of all the nodes in the mesh.
.. literalinclude:: ../../../../source/standalone/tutorials/01_assets/run_deformable_object.py
:language: python
:start-at: # update buffers
:end-at: print(f"Root position (in world): {cube_object.data.root_pos_w[:, :3]}")
:end-at: print(f"Root position (in world): {cube_object.data.root_link_pos_w[:, :3]}")


The Code Execution
Expand Down
2 changes: 1 addition & 1 deletion docs/source/tutorials/01_assets/run_rigid_object.rst
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ desired state of the rigid object prim into the world frame before setting it.
We use the :attr:`assets.RigidObject.data.default_root_state` attribute to get the default root state of the
spawned rigid object prims. This default state can be configured from the :attr:`assets.RigidObjectCfg.init_state`
attribute, which we left as identity in this tutorial. We then randomize the translation of the root state and
set the desired state of the rigid object prim using the :meth:`assets.RigidObject.write_root_state_to_sim` method.
set the desired state of the rigid object prim using the :meth:`assets.RigidObject.write_root_link_pose_to_sim` and :meth:`assets.RigidObject.write_root_com_velocity_to_sim` methods.
As the name suggests, this method writes the root state of the rigid object prim into the simulation buffer.

.. literalinclude:: ../../../../source/standalone/tutorials/01_assets/run_rigid_object.py
Expand Down
2 changes: 1 addition & 1 deletion docs/source/tutorials/05_controllers/run_diff_ik.rst
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ joint positions, current end-effector pose, and the Jacobian matrix.

While the attribute :attr:`assets.ArticulationData.joint_pos` provides the joint positions,
we only want the joint positions of the robot's arm, and not the gripper. Similarly, while
the attribute :attr:`assets.ArticulationData.body_state_w` provides the state of all the
the attribute :attr:`assets.ArticulationData.body_link_state_w` provides the state of all the
robot's bodies, we only want the state of the robot's end-effector. Thus, we need to
index into these arrays to obtain the desired quantities.

Expand Down
Loading

0 comments on commit da0a686

Please sign in to comment.