Skip to content

Commit

Permalink
Update assets
Browse files Browse the repository at this point in the history
  • Loading branch information
Dhoeller19 committed Jun 2, 2024
1 parent 7ceccc0 commit 019d2a2
Show file tree
Hide file tree
Showing 17 changed files with 125 additions and 146 deletions.
19 changes: 1 addition & 18 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
![Example Tasks created with Isaac Lab](docs/source/_static/tasks.jpg)
![Isaac Lab](docs/source/_static/isaaclab.jpg)

---

Expand Down Expand Up @@ -54,20 +54,3 @@ or opening a question on its [forums](https://forums.developer.nvidia.com/c/agx-
NVIDIA Isaac Sim is available freely under [individual license](https://www.nvidia.com/en-us/omniverse/download/). For more information about its license terms, please check [here](https://docs.omniverse.nvidia.com/app_isaacsim/common/NVIDIA_Omniverse_License_Agreement.html#software-support-supplement).

The Isaac Lab framework is released under [BSD-3 License](LICENSE). The license files of its dependencies and assets are present in the [`docs/licenses`](docs/licenses) directory.

## Citing

If you use this framework in your work, please cite [this paper](https://arxiv.org/abs/2301.04195):

```text
@article{mittal2023orbit,
author={Mittal, Mayank and Yu, Calvin and Yu, Qinxi and Liu, Jingzhou and Rudin, Nikita and Hoeller, David and Yuan, Jia Lin and Singh, Ritvik and Guo, Yunrong and Mazhar, Hammad and Mandlekar, Ajay and Babich, Buck and State, Gavriel and Hutter, Marco and Garg, Animesh},
journal={IEEE Robotics and Automation Letters},
title={Orbit: A Unified Simulation Framework for Interactive Robot Learning Environments},
year={2023},
volume={8},
number={6},
pages={3740-3747},
doi={10.1109/LRA.2023.3270034}
}
```
19 changes: 0 additions & 19 deletions docs/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -24,25 +24,6 @@ For more information about the framework, please refer to the `paper <https://ar
:alt: Example tasks created using Isaac Lab


Citing
======

If you use Isaac Lab in your research, please use the following BibTeX entry:

.. code:: bibtex
@article{mittal2023orbit,
author={Mittal, Mayank and Yu, Calvin and Yu, Qinxi and Liu, Jingzhou and Rudin, Nikita and Hoeller, David and Yuan, Jia Lin and Singh, Ritvik and Guo, Yunrong and Mazhar, Hammad and Mandlekar, Ajay and Babich, Buck and State, Gavriel and Hutter, Marco and Garg, Animesh},
journal={IEEE Robotics and Automation Letters},
title={Orbit: A Unified Simulation Framework for Interactive Robot Learning Environments},
year={2023},
volume={8},
number={6},
pages={3740-3747},
doi={10.1109/LRA.2023.3270034}
}
License
=======

Expand Down
Binary file added docs/source/_static/isaaclab.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 removed docs/source/_static/tasks.jpg
Binary file not shown.
2 changes: 1 addition & 1 deletion docs/source/setup/faq.rst
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ a starting point to understand what is possible with the simulators for robot le
can be used for benchmarking but are not designed for developing and testing custom environments and algorithms.
This is where Isaac Lab comes in.

Isaac Lab :cite:`mittal2023orbit` is built on top of Isaac Sim to provide a unified and flexible framework
Isaac Lab is built on top of Isaac Sim to provide a unified and flexible framework
for robot learning that exploits latest simulation technologies. It is designed to be modular and extensible,
and aims to simplify common workflows in robotics research (such as RL, learning from demonstrations, and
motion planning). While it includes some pre-built environments, sensors, and tasks, its main goal is to
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
#
# SPDX-License-Identifier: BSD-3-Clause

"""Configuration for the Mujoco Ant robot"""
"""Configuration for the Mujoco Ant robot."""

from __future__ import annotations

Expand All @@ -12,6 +12,10 @@
from omni.isaac.lab.assets import ArticulationCfg
from omni.isaac.lab.utils.assets import ISAAC_NUCLEUS_DIR

##
# Configuration
##

ANT_CFG = ArticulationCfg(
prim_path="{ENV_REGEX_NS}/Robot",
spawn=sim_utils.UsdFileCfg(
Expand Down Expand Up @@ -48,3 +52,4 @@
),
},
)
"""Configuration for the Mujoco Ant robot."""
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,10 @@
from omni.isaac.lab.assets import ArticulationCfg
from omni.isaac.lab.utils.assets import ISAACLAB_NUCLEUS_DIR

##
# Configuration
##

CARTPOLE_CFG = ArticulationCfg(
spawn=sim_utils.UsdFileCfg(
usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Classic/Cartpole/cartpole.usd",
Expand Down Expand Up @@ -45,3 +49,4 @@
),
},
)
"""Configuration for a simple Cartpole robot."""
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@
# Configuration
##


CASSIE_CFG = ArticulationCfg(
spawn=sim_utils.UsdFileCfg(
usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Agility/Cassie/cassie.usd",
Expand Down

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
#
# SPDX-License-Identifier: BSD-3-Clause

"""Configuration for the Mujoco Ant robot"""
"""Configuration for the Mujoco Humanoid robot."""

from __future__ import annotations

Expand All @@ -12,6 +12,10 @@
from omni.isaac.lab.assets import ArticulationCfg
from omni.isaac.lab.utils.assets import ISAAC_NUCLEUS_DIR

##
# Configuration
##

HUMANOID_CFG = ArticulationCfg(
prim_path="{ENV_REGEX_NS}/Robot",
spawn=sim_utils.UsdFileCfg(
Expand Down Expand Up @@ -62,3 +66,4 @@
),
},
)
"""Configuration for the Mujoco Humanoid robot."""
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,6 @@
# Configuration
##


KINOVA_JACO2_N7S300_CFG = ArticulationCfg(
spawn=sim_utils.UsdFileCfg(
usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Kinova/Jaco2/J2N7S300/j2n7s300_instanceable.usd",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
#
# SPDX-License-Identifier: BSD-3-Clause

"""Configuration for the Quadcopters"""
"""Configuration for the quadcopters"""

from __future__ import annotations

Expand All @@ -12,6 +12,10 @@
from omni.isaac.lab.assets import ArticulationCfg
from omni.isaac.lab.utils.assets import ISAAC_NUCLEUS_DIR

##
# Configuration
##

CRAZYFLIE_CFG = ArticulationCfg(
prim_path="{ENV_REGEX_NS}/Robot",
spawn=sim_utils.UsdFileCfg(
Expand Down Expand Up @@ -50,3 +54,4 @@
),
},
)
"""Configuration for the Crazyflie quadcopter."""
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,10 @@
from omni.isaac.lab.assets.articulation import ArticulationCfg
from omni.isaac.lab.utils.assets import ISAAC_NUCLEUS_DIR

##
# Configuration
##

RIDGEBACK_FRANKA_PANDA_CFG = ArticulationCfg(
spawn=sim_utils.UsdFileCfg(
usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/Clearpath/RidgebackFranka/ridgeback_franka.usd",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@
# Configuration
##


SAWYER_CFG = ArticulationCfg(
spawn=sim_utils.UsdFileCfg(
usd_path=f"{ISAAC_NUCLEUS_DIR}/Robots/RethinkRobotics/sawyer_instanceable.usd",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,12 +10,13 @@
* :obj:`UNITREE_A1_CFG`: Unitree A1 robot with DC motor model for the legs
* :obj:`UNITREE_GO1_CFG`: Unitree Go1 robot with actuator net model for the legs
* :obj:`UNITREE_GO2_CFG`: Unitree Go2 robot with DC motor model for the legs
* :obj:`H1_CFG`: H1 humanoid robot
Reference: https://github.com/unitreerobotics/unitree_ros
"""

import omni.isaac.lab.sim as sim_utils
from omni.isaac.lab.actuators import ActuatorNetMLPCfg, DCMotorCfg
from omni.isaac.lab.actuators import ActuatorNetMLPCfg, DCMotorCfg, ImplicitActuatorCfg
from omni.isaac.lab.assets.articulation import ArticulationCfg
from omni.isaac.lab.utils.assets import ISAACLAB_NUCLEUS_DIR

Expand Down Expand Up @@ -173,3 +174,94 @@
},
)
"""Configuration of Unitree Go2 using DC-Motor actuator model."""


H1_CFG = ArticulationCfg(
spawn=sim_utils.UsdFileCfg(
usd_path=f"{ISAACLAB_NUCLEUS_DIR}/Robots/Unitree/H1/h1.usd",
activate_contact_sensors=True,
rigid_props=sim_utils.RigidBodyPropertiesCfg(
disable_gravity=False,
retain_accelerations=False,
linear_damping=0.0,
angular_damping=0.0,
max_linear_velocity=1000.0,
max_angular_velocity=1000.0,
max_depenetration_velocity=1.0,
),
articulation_props=sim_utils.ArticulationRootPropertiesCfg(
enabled_self_collisions=False, solver_position_iteration_count=4, solver_velocity_iteration_count=4
),
),
init_state=ArticulationCfg.InitialStateCfg(
pos=(0.0, 0.0, 1.05),
joint_pos={
".*_hip_yaw": 0.0,
".*_hip_roll": 0.0,
".*_hip_pitch": -0.28, # -16 degrees
".*_knee": 0.79, # 45 degrees
".*_ankle": -0.52, # -30 degrees
"torso": 0.0,
".*_shoulder_pitch": 0.28,
".*_shoulder_roll": 0.0,
".*_shoulder_yaw": 0.0,
".*_elbow": 0.52,
},
joint_vel={".*": 0.0},
),
soft_joint_pos_limit_factor=0.9,
actuators={
"legs": ImplicitActuatorCfg(
joint_names_expr=[".*_hip_yaw", ".*_hip_roll", ".*_hip_pitch", ".*_knee", "torso"],
effort_limit=300,
velocity_limit=100.0,
stiffness={
".*_hip_yaw": 150.0,
".*_hip_roll": 150.0,
".*_hip_pitch": 200.0,
".*_knee": 200.0,
"torso": 200.0,
},
damping={
".*_hip_yaw": 5.0,
".*_hip_roll": 5.0,
".*_hip_pitch": 5.0,
".*_knee": 5.0,
"torso": 5.0,
},
),
"feet": ImplicitActuatorCfg(
joint_names_expr=[".*_ankle"],
effort_limit=100,
velocity_limit=100.0,
stiffness={".*_ankle": 20.0},
damping={".*_ankle": 4.0},
),
"arms": ImplicitActuatorCfg(
joint_names_expr=[".*_shoulder_pitch", ".*_shoulder_roll", ".*_shoulder_yaw", ".*_elbow"],
effort_limit=300,
velocity_limit=100.0,
stiffness={
".*_shoulder_pitch": 40.0,
".*_shoulder_roll": 40.0,
".*_shoulder_yaw": 40.0,
".*_elbow": 40.0,
},
damping={
".*_shoulder_pitch": 10.0,
".*_shoulder_roll": 10.0,
".*_shoulder_yaw": 10.0,
".*_elbow": 10.0,
},
),
},
)
"""Configuration for the Unitree H1 Humanoid robot."""


H1_MINIMAL_CFG = H1_CFG.copy()
H1_MINIMAL_CFG.spawn.usd_path = f"{ISAACLAB_NUCLEUS_DIR}/Robots/Unitree/H1/h1_minimal.usd"
"""Configuration for the Unitree H1 Humanoid robot with fewer collision meshes.
This configuration removes most collision meshes to speed up simulation.
"""
Loading

0 comments on commit 019d2a2

Please sign in to comment.