diff --git a/README.md b/README.md
index 74e3a07..02aeb1f 100644
--- a/README.md
+++ b/README.md
@@ -42,6 +42,11 @@ cd loco-mujoco
pip install -e .
```
+> [!NOTE]
+> We fixed the version of MuJoCo to 2.3.7 during installation since we found that there are slight
+> differences in the simulation, which made testing very difficult. However, in practice, you can
+> use any newer version of MuJoCo! Just install it after installing LocoMuJoCo.
+
### Download the Datasets
After installing LocoMuJoCo, new commands for downloading the datasets will be setup for you.
You have the choice of downloading all datasets available or only the ones you need.
diff --git a/docs/conf.py b/docs/conf.py
index 29059d2..0cbb71f 100644
--- a/docs/conf.py
+++ b/docs/conf.py
@@ -8,25 +8,26 @@
import os
import sys
+from loco_mujoco import __version__
sys.path.insert(0, os.path.abspath(".."))
project = 'LocoMuJoCo'
copyright = '2024, Firas Al-Hafez'
author = 'Firas Al-Hafez'
-release = 'v0.2.2'
+release = 'v' + __version__
# -- General configuration ---------------------------------------------------
# https://www.sphinx-doc.org/en/master/usage/configuration.html#general-configuration
-extensions = ['sphinx.ext.todo', 'sphinx.ext.viewcode', 'sphinx.ext.autodoc', "m2r2"]
+extensions = ['sphinx.ext.todo', 'sphinx.ext.viewcode', 'sphinx.ext.autodoc', "m2r2", 'sphinx.ext.napoleon']
templates_path = ['_templates']
exclude_patterns = ['_build', 'Thumbs.db', '.DS_Store']
add_module_names = False
autodoc_member_order = 'groupwise'
source_suffix = [".rst", ".md"]
-
+napoleon_google_docstring = True
# -- Options for HTML output -------------------------------------------------
# https://www.sphinx-doc.org/en/master/usage/configuration.html#options-for-html-output
diff --git a/docs/source/humanoids/unitreeg1.rst b/docs/source/humanoids/unitreeg1.rst
new file mode 100644
index 0000000..08d8f75
--- /dev/null
+++ b/docs/source/humanoids/unitreeg1.rst
@@ -0,0 +1,13 @@
+Unitree G1
+=======================================================
+
+.. image:: https://github.com/robfiras/loco-mujoco/assets/69359729/be7c3b29-03db-49c2-8e27-527562218f74
+ :width: 49%
+.. image:: https://github.com/robfiras/loco-mujoco/assets/69359729/23cf5988-7326-453e-af24-0f0adc255c9c
+ :width: 49%
+
+.. automodule:: loco_mujoco.environments.humanoids.unitreeG1
+ :members:
+ :undoc-members:
+ :private-members:
+ :show-inheritance:
diff --git a/docs/source/loco_mujoco.environments.humanoids.rst b/docs/source/loco_mujoco.environments.humanoids.rst
index 79ac6a4..e089972 100644
--- a/docs/source/loco_mujoco.environments.humanoids.rst
+++ b/docs/source/loco_mujoco.environments.humanoids.rst
@@ -8,6 +8,7 @@ Here you find an overview of the API of all Humanoid environments.
./humanoids/talos.rst
./humanoids/atlas.rst
./humanoids/unitreeh1.rst
+ ./humanoids/unitreeg1.rst
./humanoids/torque_humanoid.rst
./humanoids/muscle_humanoid.rst
./humanoids/base_humanoids.rst
diff --git a/docs/source/loco_mujoco.installation.rst b/docs/source/loco_mujoco.installation.rst
index 65556ab..380258f 100644
--- a/docs/source/loco_mujoco.installation.rst
+++ b/docs/source/loco_mujoco.installation.rst
@@ -17,6 +17,10 @@ or you do an editable installation by cloning this repository and then running:
cd loco-mujoco
pip install -e .
+.. note::
+ We fixed the version of MuJoCo to 2.3.7 during installation since we found that there are slight
+ differences in the simulation, which made testing very difficult. However, in practice, you can
+ use any newer version of MuJoCo! Just install it after installing LocoMuJoCo.
Download the Datasets
---------------------
diff --git a/docs/utils.py b/docs/utils.py
index 3c655e1..18259ae 100644
--- a/docs/utils.py
+++ b/docs/utils.py
@@ -1,6 +1,6 @@
import inspect
import loco_mujoco
-from loco_mujoco.environments import HumanoidTorque, HumanoidMuscle, UnitreeA1
+from loco_mujoco.environments import HumanoidTorque, HumanoidMuscle, UnitreeA1, UnitreeG1
from mushroom_rl.utils.mujoco import *
@@ -136,7 +136,10 @@ def get_action_space_table_docs(env, use_muscles=False):
else:
motors_to_remove = []
except :
- action_spec = env._get_action_specification(use_muscles)
+ if type(env) == UnitreeG1:
+ action_spec = env._get_action_specification()
+ else:
+ action_spec = env._get_action_specification(use_muscles)
_, motors_to_remove, _, _ = env._get_xml_modifications()
header = ["Index", "Name in XML", "Control Min", "Control Max", "Disabled"]
@@ -160,14 +163,14 @@ def get_action_space_table_docs(env, use_muscles=False):
if __name__ == "__main__":
# # Talos
- env = loco_mujoco.LocoEnv.make("Talos", disable_arms=False, disable_back=False)
- additional_info = [["Mass of the Weight", "0.0", "inf", "Only Enabled for Carry Task", "1", "Mass [kg]"],
- ["3D linear Forces between Right Foot and Floor", "0.0", "inf", "True", "3", "Force [N]"],
- ["3D linear Forces between Left Foot and Floor", "0.0", "inf", "True", "3", "Force [N]"]]
- print(get_obs_space_table_docs(env, additional_info)[0],
- "\nNumber of obs that are on by default: ", get_obs_space_table_docs(env, additional_info)[1], "\n")
- print(get_action_space_table_docs(env)[0],
- "\nNumber of actions that are on by default: ", get_action_space_table_docs(env)[1])
+ # env = loco_mujoco.LocoEnv.make("Talos", disable_arms=False, disable_back=False)
+ # additional_info = [["Mass of the Weight", "0.0", "inf", "Only Enabled for Carry Task", "1", "Mass [kg]"],
+ # ["3D linear Forces between Right Foot and Floor", "0.0", "inf", "True", "3", "Force [N]"],
+ # ["3D linear Forces between Left Foot and Floor", "0.0", "inf", "True", "3", "Force [N]"]]
+ # print(get_obs_space_table_docs(env, additional_info)[0],
+ # "\nNumber of obs that are on by default: ", get_obs_space_table_docs(env, additional_info)[1], "\n")
+ # print(get_action_space_table_docs(env)[0],
+ # "\nNumber of actions that are on by default: ", get_action_space_table_docs(env)[1])
# # Atlas
# env = loco_mujoco.LocoEnv.make("Atlas", disable_arms=False, disable_back=False)
@@ -191,6 +194,15 @@ def get_action_space_table_docs(env, use_muscles=False):
# print(get_action_space_table_docs(env)[0],
# "\nNumber of actions that are on by default: ", get_action_space_table_docs(env)[1])
+ # UnitreeG1
+ env = loco_mujoco.LocoEnv.make("UnitreeG1", disable_arms=False, disable_back=False)
+ additional_info = [["3D linear Forces between Right Foot and Floor", "0.0", "inf", "True", "3", "Force [N]"],
+ ["3D linear Forces between Left Foot and Floor", "0.0", "inf", "True", "3", "Force [N]"]]
+ print(get_obs_space_table_docs(env, additional_info)[0],
+ "\nNumber of obs that are on by default: ", get_obs_space_table_docs(env, additional_info)[1], "\n")
+ print(get_action_space_table_docs(env)[0],
+ "\nNumber of actions that are on by default: ", get_action_space_table_docs(env)[1])
+
# Torque Humanoid
# env = loco_mujoco.LocoEnv.make("HumanoidTorque", disable_back=False, disable_arms=False)
# additional_info = [["3D linear Forces between Back Right Foot and Floor", "0.0", "inf", "True", "3", "Force [N]"],
diff --git a/examples/imitation_learning/confs.yaml b/examples/imitation_learning/confs.yaml
index 9ef85d9..1f35f15 100644
--- a/examples/imitation_learning/confs.yaml
+++ b/examples/imitation_learning/confs.yaml
@@ -129,6 +129,25 @@ UnitreeH1:
use_noisy_targets: False
last_policy_activation: "identity"
+UnitreeG1:
+ algorithm: "VAIL"
+ algorithm_config:
+ std_0: 0.5
+ info_constraint: 0.1
+ lr_beta: 0.00001
+ z_dim: 128
+ disc_only_states: True
+ disc_use_next_states: False
+ train_disc_n_th_epoch: 3
+ disc_batch_size: 2048
+ learning_rate_critic: 1.0e-4
+ learning_rate_disc: 5.0e-5
+ policy_entr_coef: 1.0e-3
+ max_kl: 5.0e-3
+ n_epochs_cg: 25
+ use_noisy_targets: False
+ last_policy_activation: "identity"
+
UnitreeA1.simple:
algorithm: "VAIL"
algorithm_config:
diff --git a/examples/imitation_learning/launcher.py b/examples/imitation_learning/launcher.py
index 1d3695a..68ec4b3 100644
--- a/examples/imitation_learning/launcher.py
+++ b/examples/imitation_learning/launcher.py
@@ -31,6 +31,7 @@
env_ids = ["Atlas.walk", "Atlas.carry",
"Talos.walk", "Talos.carry",
"UnitreeH1.walk", "UnitreeH1.run", "UnitreeH1.carry",
+ "UnitreeG1.walk", "UnitreeG1.run",
"HumanoidTorque.walk", "HumanoidTorque.run",
"HumanoidMuscle.walk", "HumanoidMuscle.run",
"UnitreeA1.simple", "UnitreeA1.hard"]
diff --git a/examples/replay_datasets/record_all.py b/examples/replay_datasets/record_all.py
index 1640c00..80acf3d 100644
--- a/examples/replay_datasets/record_all.py
+++ b/examples/replay_datasets/record_all.py
@@ -11,12 +11,13 @@ def experiment(seed=0):
envs = LocoEnv.get_all_task_names()
for env in envs:
+
if "real" in env:
replay_params = dict(n_episodes=15, n_steps_per_episode=250, record=True) if "Unitree.hard" in env or \
".all" in env or ".carry" in env \
else dict(n_episodes=3, n_steps_per_episode=500, record=True)
- if ("Humanoid" in env or "Atlas.walk" in env) and not "carry" in env:
+ if ("Humanoid" in env or "Atlas.walk" in env or "UnitreeG1" in env) and not "carry" in env:
env_params = dict(disable_arms=False)
else:
env_params = dict()
diff --git a/loco_mujoco/datasets/humanoids/real/mini_datasets/02-constspeed_UnitreeG1.npz b/loco_mujoco/datasets/humanoids/real/mini_datasets/02-constspeed_UnitreeG1.npz
new file mode 100644
index 0000000..1847f9f
Binary files /dev/null and b/loco_mujoco/datasets/humanoids/real/mini_datasets/02-constspeed_UnitreeG1.npz differ
diff --git a/loco_mujoco/datasets/humanoids/real/mini_datasets/05-run_UnitreeG1.npz b/loco_mujoco/datasets/humanoids/real/mini_datasets/05-run_UnitreeG1.npz
new file mode 100644
index 0000000..cd670f0
Binary files /dev/null and b/loco_mujoco/datasets/humanoids/real/mini_datasets/05-run_UnitreeG1.npz differ
diff --git a/loco_mujoco/environments/README.md b/loco_mujoco/environments/README.md
index f950d0c..58db233 100644
--- a/loco_mujoco/environments/README.md
+++ b/loco_mujoco/environments/README.md
@@ -9,12 +9,14 @@ The status of a dataset can be seen down below. ✅ means it is already availabl
| ![out9](https://github.com/robfiras/loco-mujoco/assets/69359729/2c7aeb58-65a6-427c-8b12-197c96410cd8) | HumanoidMuscle4Ages.walk.2 HumanoidMuscle4Ages.run.2 | real: ✅
perfect: 🔶
preference: 🔶 | Task of a (~5-6 year old) **Muscle** Humanoid Walking or Running Straight. |
| ![out9](https://github.com/robfiras/loco-mujoco/assets/69359729/600a917f-c784-4b5e-ac99-9472711de843) | HumanoidMuscle4Ages.walk.1 HumanoidMuscle4Ages.run.1 | real: ✅
perfect: 🔶
preference: 🔶 | Task of a (~2 year old) **Muscle** Humanoid Walking or Running Straight. |
| ![out39](https://github.com/robfiras/loco-mujoco/assets/69359729/cf32520f-5a2e-401a-9f2e-b8033ef7109c) | HumanoidTorque.walk HumanoidTorque.run HumanoidTorque4Ages.walk.4 HumanoidTorque.run HumanoidTorque4Ages.run.4 | real: ✅
perfect: ✅
preference: 🔶| Task of an adult **Torque** Humanoid Walking or Running Straight. |
- | ![out3](https://github.com/robfiras/loco-mujoco/assets/69359729/352f3594-8903-4eaf-a223-f751b590f4ec) | HumanoidTorque4Ages.walk.3 HumanoidTorque4Ages.run.3 | real: ✅
perfect: 🔶
preference: 🔶 | Task of a (~12 year old) **Torque** Humanoid Walking or Running Straight. |
- | ![out5](https://github.com/robfiras/loco-mujoco/assets/69359729/06c83af9-3c45-43a1-8173-aa1d8771fe4c) | HumanoidTorque4Ages.walk.2 HumanoidTorque4Ages.run.2 | real: ✅
perfect: 🔶
preference: 🔶 | Task of a (~5-6 year old) **Torque** Humanoid Walking or Running Straight. |
- | ![out3](https://github.com/robfiras/loco-mujoco/assets/69359729/5ec93baa-bed8-4d9f-b983-3bc12264b9b6) | HumanoidTorque4Ages.walk.1 HumanoidTorque4Ages.run.1 | real: ✅
perfect: 🔶
preference: 🔶 | Task of a (~2 year old) **Torque** Humanoid Walking or Running Straight. |
+ | ![out3](https://github.com/robfiras/loco-mujoco/assets/69359729/352f3594-8903-4eaf-a223-f751b590f4ec) | HumanoidTorque4Ages.walk.3 HumanoidTorque4Ages.run.3 | real: ✅
perfect: ✅
preference: 🔶 | Task of a (~12 year old) **Torque** Humanoid Walking or Running Straight. |
+ | ![out5](https://github.com/robfiras/loco-mujoco/assets/69359729/06c83af9-3c45-43a1-8173-aa1d8771fe4c) | HumanoidTorque4Ages.walk.2 HumanoidTorque4Ages.run.2 | real: ✅
perfect: ✅
preference: 🔶 | Task of a (~5-6 year old) **Torque** Humanoid Walking or Running Straight. |
+ | ![out3](https://github.com/robfiras/loco-mujoco/assets/69359729/5ec93baa-bed8-4d9f-b983-3bc12264b9b6) | HumanoidTorque4Ages.walk.1 HumanoidTorque4Ages.run.1 | real: ✅
perfect: ✅
preference: 🔶 | Task of a (~2 year old) **Torque** Humanoid Walking or Running Straight. |
| ![out8](https://github.com/robfiras/loco-mujoco/assets/69359729/fed0315c-921e-4b2e-a9c2-54b85198ef65) | UnitreeH1.walk | real: ✅
perfect: ✅
preference: 🔶| UnitreeH1 Straight Walking Task. |
| ![out9](https://github.com/robfiras/loco-mujoco/assets/69359729/ab0dec59-fc24-4763-8ff6-38d58ac3b3de) | UnitreeH1.run | real: ✅
perfect: ✅
preference: 🔶| UnitreeH1 Straight Running Task. |
| ![out3](https://github.com/robfiras/loco-mujoco/assets/69359729/851ff3c0-d05f-4de1-a00b-7b3204056e2f) | UnitreeH1.carry | real: ✅
perfect: 🔶
preference: 🔶| UnitreeH1 Carry Task. |
+ | ![out8](https://github.com/robfiras/loco-mujoco/assets/69359729/e9a33e94-65e4-48f5-8d7a-3d103c4ec7f5) | UnitreeG1.walk | real: ✅
perfect: 🔶
preference: 🔶| UnitreeG1 Straight Walking Task. |
+ | ![out9](https://github.com/robfiras/loco-mujoco/assets/69359729/57292ef1-c152-4cd3-b7c1-d9a1e0633481) | UnitreeG1.run | real: ✅
perfect: 🔶
preference: 🔶| UnitreeG1 Straight Running Task. |
| ![out7](https://github.com/robfiras/loco-mujoco/assets/69359729/22c7bb0c-ff92-4e99-a964-7654df6d22c4) | Talos.walk | real: ✅
perfect: ✅
preference: 🔶| Talos Straight Walking Task. |
| ![out3](https://github.com/robfiras/loco-mujoco/assets/69359729/0ba1f0e7-1f3d-4088-a44f-0a53bec1cf3a) | Talos.carry | real: ✅
perfect: 🔶
preference: 🔶| Talos Carry Task. |
| ![out13](https://github.com/robfiras/loco-mujoco/assets/69359729/1ff09d98-e46b-429c-ac07-87de58853d28) | Atlas.walk | real: ✅
perfect: ✅
preference: 🔶| Atlas Straight Walking Task. |
diff --git a/loco_mujoco/environments/base.py b/loco_mujoco/environments/base.py
index 87ffe6a..69a3bb2 100644
--- a/loco_mujoco/environments/base.py
+++ b/loco_mujoco/environments/base.py
@@ -37,7 +37,7 @@ def __init__(self, xml_handles, action_spec, observation_spec, collision_groups=
Constructor.
Args:
- xml_handle : MuJoCo xml handle.
+ xml_handles : MuJoCo xml handles.
actuation_spec (list): A list specifying the names of the joints
which should be controllable by the agent. Can be left empty
when all actuators should be used;
@@ -86,6 +86,7 @@ def __init__(self, xml_handles, action_spec, observation_spec, collision_groups=
if type(xml_handles) != list:
xml_handles = [xml_handles]
+ self._xml_handles = xml_handles
if collision_groups is None:
collision_groups = list()
@@ -128,7 +129,7 @@ def __init__(self, xml_handles, action_spec, observation_spec, collision_groups=
self.mean_grf = self._setup_ground_force_statistics()
# dataset dummy
- self._dataset= None
+ self._dataset = None
if traj_params:
self.trajectories = None
@@ -547,6 +548,22 @@ def load_dataset_and_get_traj_files(self, dataset_path, freq=None):
return trajectories
+ @property
+ def xml_handle(self):
+ """ Returns the XML handle of the environment. This will raise an error if the environment contains more
+ than one xml_handle. """
+
+ if len(self._xml_handles) > 1:
+ raise ValueError("This environment contains multiple models and hence multiple xml_handles. Use the "
+ "property \"xml_handles\" instead.")
+ return self._xml_handles[0]
+
+ @property
+ def xml_handles(self):
+ """ Returns all XML handles of the environment. """
+
+ return self._xml_handles
+
def _get_observation_space(self):
"""
Returns a tuple of the lows and highs (np.array) of the observation space.
diff --git a/loco_mujoco/environments/humanoids/atlas.py b/loco_mujoco/environments/humanoids/atlas.py
index ba8bfbe..de1e73e 100644
--- a/loco_mujoco/environments/humanoids/atlas.py
+++ b/loco_mujoco/environments/humanoids/atlas.py
@@ -16,7 +16,7 @@ class Atlas(BaseRobotHumanoid):
Description
------------
- Mujoco simulation of the Atlas robot. Optionally, Atlas can carry
+ Mujoco environment of the Atlas robot. Optionally, Atlas can carry
a weight. This environment can be partially observable by hiding
some of the state space entries from the policy using a state mask.
Hidable entries are "positions", "velocities", "foot_forces",
diff --git a/loco_mujoco/environments/humanoids/base_humanoid.py b/loco_mujoco/environments/humanoids/base_humanoid.py
index 836de9f..a9b8c0b 100644
--- a/loco_mujoco/environments/humanoids/base_humanoid.py
+++ b/loco_mujoco/environments/humanoids/base_humanoid.py
@@ -13,7 +13,7 @@
class BaseHumanoid(LocoEnv):
"""
- MuJoCo simulation of a base humanoid model.
+ Mujoco environment of a base humanoid model.
"""
diff --git a/loco_mujoco/environments/humanoids/base_humanoid_4_ages.py b/loco_mujoco/environments/humanoids/base_humanoid_4_ages.py
index 430f4fc..0a4f682 100644
--- a/loco_mujoco/environments/humanoids/base_humanoid_4_ages.py
+++ b/loco_mujoco/environments/humanoids/base_humanoid_4_ages.py
@@ -16,7 +16,7 @@
class BaseHumanoid4Ages(BaseHumanoid):
"""
- MuJoCo simulation of 4 simplified humanoid models.
+ Mujoco environment of 4 simplified humanoid models.
At the beginning of each episode, one of the four humanoid models are
sampled and used to simulate a trajectory. The different humanoids should
resemble an adult, a teenager (∼12 years), a child (∼5 years), and a
diff --git a/loco_mujoco/environments/humanoids/base_robot_humanoid.py b/loco_mujoco/environments/humanoids/base_robot_humanoid.py
index 00b9c5d..92f8957 100644
--- a/loco_mujoco/environments/humanoids/base_robot_humanoid.py
+++ b/loco_mujoco/environments/humanoids/base_robot_humanoid.py
@@ -11,7 +11,7 @@
class BaseRobotHumanoid(LocoEnv):
"""
- Base Class for the Mujoco simulation of Atlas, UnitreeH1 and Talos.
+ Base Class for the Mujoco environment of Atlas, UnitreeH1/G1 and Talos.
"""
diff --git a/loco_mujoco/environments/humanoids/humanoids.py b/loco_mujoco/environments/humanoids/humanoids.py
index f8261fb..391b2bb 100644
--- a/loco_mujoco/environments/humanoids/humanoids.py
+++ b/loco_mujoco/environments/humanoids/humanoids.py
@@ -10,7 +10,7 @@ class HumanoidTorque(BaseHumanoid):
Description
------------
- MuJoCo simulation of a humanoid model with one torque actuator per joint.
+ Mujoco environment of a humanoid model with one torque actuator per joint.
Tasks
-----------------
@@ -323,7 +323,7 @@ class HumanoidMuscle(BaseHumanoid):
Description
------------
- MuJoCo simulation of a humanoid model with muscle actuation.
+ Mujoco environment of a humanoid model with muscle actuation.
.. note:: This Humanoid consists of 92 muscles on the lower limb. The upper body is torque actuated.
@@ -788,7 +788,7 @@ def generate(task="walk", dataset_type="real", **kwargs):
class HumanoidTorque4Ages(BaseHumanoid4Ages):
"""
- MuJoCo simulation of 4 simplified humanoid models with one torque actuator per joint.
+ Mujoco environment of 4 simplified humanoid models with one torque actuator per joint.
At the beginning of each episode, one of the four humanoid models are randomly
sampled and used to simulate a trajectory. The different humanoids should
resemble an adult, a teenager (∼12 years), a child (∼5 years), and a
@@ -895,7 +895,7 @@ def generate(task="walk", mode="all", dataset_type="real", **kwargs):
class HumanoidMuscle4Ages(BaseHumanoid4Ages):
"""
- MuJoCo simulation of 4 simplified humanoid models with muscle actuation.
+ Mujoco environment of 4 simplified humanoid models with muscle actuation.
At the beginning of each episode, one of the four humanoid models are
sampled and used to simulate a trajectory. The different humanoids should
resemble an adult, a teenager (∼12 years), a child (∼5 years), and a
diff --git a/loco_mujoco/environments/humanoids/talos.py b/loco_mujoco/environments/humanoids/talos.py
index 0d5d4f4..b869fcf 100644
--- a/loco_mujoco/environments/humanoids/talos.py
+++ b/loco_mujoco/environments/humanoids/talos.py
@@ -16,7 +16,7 @@ class Talos(BaseRobotHumanoid):
Description
------------
- Mujoco simulation of the Talos robot. Optionally, Talos can carry
+ Mujoco environment of the Talos robot. Optionally, Talos can carry
a weight. This environment can be partially observable by hiding
some of the state space entries from the policy using a state mask.
Hidable entries are "positions", "velocities", "foot_forces",
diff --git a/loco_mujoco/environments/humanoids/unitreeG1.py b/loco_mujoco/environments/humanoids/unitreeG1.py
index 80500f5..d8c40fb 100644
--- a/loco_mujoco/environments/humanoids/unitreeG1.py
+++ b/loco_mujoco/environments/humanoids/unitreeG1.py
@@ -16,7 +16,7 @@ class UnitreeG1(BaseRobotHumanoid):
Description
------------
- Mujoco simulation of the Unitree G1 robot.
+ Mujoco environment of the Unitree G1 robot.
Tasks
-----------------
@@ -34,167 +34,186 @@ class UnitreeG1(BaseRobotHumanoid):
The observation space has the following properties *by default* (i.e., only obs with Disabled == False):
- | For walking task: :code:`(min=-inf, max=inf, dim=32, dtype=float32)`
- | For running task: :code:`(min=-inf, max=inf, dim=32, dtype=float32)`
+ | For walking task: :code:`(min=-inf, max=inf, dim=56, dtype=float32)`
+ | For running task: :code:`(min=-inf, max=inf, dim=56, dtype=float32)`
Some observations are **disabled by default**, but can be turned on. The detailed observation space is:
- ===== ============================================= ===== ==== =========================== === ========================
- Index Description Min Max Disabled Dim Units
- ===== ============================================= ===== ==== =========================== === ========================
- 0 Position of Joint pelvis_ty -inf inf False 1 Position [m]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 1 Position of Joint pelvis_tilt -inf inf False 1 Angle [rad]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 2 Position of Joint pelvis_list -inf inf False 1 Angle [rad]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 3 Position of Joint pelvis_rotation -inf inf False 1 Angle [rad]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 4 Position of Joint back_bkz -2.35 2.35 False 1 Angle [rad]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 5 Position of Joint l_arm_shy -2.87 2.87 True 1 Angle [rad]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 6 Position of Joint l_arm_shx -0.34 3.11 True 1 Angle [rad]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 7 Position of Joint l_arm_shz -1.3 4.45 True 1 Angle [rad]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 8 Position of Joint left_elbow -1.25 2.61 True 1 Angle [rad]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 9 Position of Joint r_arm_shy -2.87 2.87 True 1 Angle [rad]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 10 Position of Joint r_arm_shx -3.11 0.34 True 1 Angle [rad]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 11 Position of Joint r_arm_shz -4.45 1.3 True 1 Angle [rad]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 12 Position of Joint right_elbow -1.25 2.61 True 1 Angle [rad]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 13 Position of Joint hip_flexion_r -1.57 1.57 False 1 Angle [rad]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 14 Position of Joint hip_adduction_r -0.43 0.43 False 1 Angle [rad]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 15 Position of Joint hip_rotation_r -0.43 0.43 False 1 Angle [rad]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 16 Position of Joint knee_angle_r -0.26 2.05 False 1 Angle [rad]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 17 Position of Joint ankle_angle_r -0.87 0.52 False 1 Angle [rad]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 18 Position of Joint hip_flexion_l -1.57 1.57 False 1 Angle [rad]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 19 Position of Joint hip_adduction_l -0.43 0.43 False 1 Angle [rad]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 20 Position of Joint hip_rotation_l -0.43 0.43 False 1 Angle [rad]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 21 Position of Joint knee_angle_l -0.26 2.05 False 1 Angle [rad]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 22 Position of Joint ankle_angle_l -0.87 0.52 False 1 Angle [rad]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 23 Velocity of Joint pelvis_tx -inf inf False 1 Velocity [m/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 24 Velocity of Joint pelvis_tz -inf inf False 1 Velocity [m/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 25 Velocity of Joint pelvis_ty -inf inf False 1 Velocity [m/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 26 Velocity of Joint pelvis_tilt -inf inf False 1 Angular Velocity [rad/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 27 Velocity of Joint pelvis_list -inf inf False 1 Angular Velocity [rad/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 28 Velocity of Joint pelvis_rotation -inf inf False 1 Angular Velocity [rad/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 29 Velocity of Joint back_bkz -inf inf False 1 Angular Velocity [rad/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 30 Velocity of Joint l_arm_shy -inf inf True 1 Angular Velocity [rad/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 31 Velocity of Joint l_arm_shx -inf inf True 1 Angular Velocity [rad/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 32 Velocity of Joint l_arm_shz -inf inf True 1 Angular Velocity [rad/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 33 Velocity of Joint left_elbow -inf inf True 1 Angular Velocity [rad/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 34 Velocity of Joint r_arm_shy -inf inf True 1 Angular Velocity [rad/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 35 Velocity of Joint r_arm_shx -inf inf True 1 Angular Velocity [rad/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 36 Velocity of Joint r_arm_shz -inf inf True 1 Angular Velocity [rad/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 37 Velocity of Joint right_elbow -inf inf True 1 Angular Velocity [rad/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 38 Velocity of Joint hip_flexion_r -inf inf False 1 Angular Velocity [rad/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 39 Velocity of Joint hip_adduction_r -inf inf False 1 Angular Velocity [rad/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 40 Velocity of Joint hip_rotation_r -inf inf False 1 Angular Velocity [rad/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 41 Velocity of Joint knee_angle_r -inf inf False 1 Angular Velocity [rad/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 42 Velocity of Joint ankle_angle_r -inf inf False 1 Angular Velocity [rad/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 43 Velocity of Joint hip_flexion_l -inf inf False 1 Angular Velocity [rad/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 44 Velocity of Joint hip_adduction_l -inf inf False 1 Angular Velocity [rad/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 45 Velocity of Joint hip_rotation_l -inf inf False 1 Angular Velocity [rad/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 46 Velocity of Joint knee_angle_l -inf inf False 1 Angular Velocity [rad/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 47 Velocity of Joint ankle_angle_l -inf inf False 1 Angular Velocity [rad/s]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 48 Mass of the Weight 0.0 inf Only Enabled for Carry Task 1 Mass [kg]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 49 3D linear Forces between Right Foot and Floor 0.0 inf True 3 Force [N]
- ----- --------------------------------------------- ----- ---- --------------------------- --- ------------------------
- 52 3D linear Forces between Left Foot and Floor 0.0 inf True 3 Force [N]
- ===== ============================================= ===== ==== =========================== === ========================
+ ===== ============================================= ======== ====== ======== === ========================
+ Index Description Min Max Disabled Dim Units
+ ===== ============================================= ======== ====== ======== === ========================
+ 0 Position of Joint pelvis_ty -inf inf False 1 Position [m]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 1 Position of Joint pelvis_tilt -inf inf False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 2 Position of Joint pelvis_list -inf inf False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 3 Position of Joint pelvis_rotation -inf inf False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 4 Position of Joint left_hip_pitch_joint -2.35 3.05 False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 5 Position of Joint left_hip_roll_joint -0.26 2.53 False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 6 Position of Joint left_hip_yaw_joint -2.75 2.75 False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 7 Position of Joint left_knee_joint -0.33489 2.5449 False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 8 Position of Joint left_ankle_pitch_joint -0.68 0.73 False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 9 Position of Joint left_ankle_roll_joint -0.2618 0.2618 False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 10 Position of Joint right_hip_pitch_joint -2.35 3.05 False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 11 Position of Joint right_hip_roll_joint -2.53 0.26 False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 12 Position of Joint right_hip_yaw_joint -2.75 2.75 False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 13 Position of Joint right_knee_joint -0.33489 2.5449 False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 14 Position of Joint right_ankle_pitch_joint -0.68 0.73 False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 15 Position of Joint right_ankle_roll_joint -0.2618 0.2618 False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 16 Position of Joint torso_joint -2.618 2.618 False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 17 Position of Joint left_shoulder_pitch_joint -2.9671 2.7925 False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 18 Position of Joint left_shoulder_roll_joint -1.5882 2.2515 False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 19 Position of Joint left_shoulder_yaw_joint -2.618 2.618 False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 20 Position of Joint left_elbow_pitch_joint -0.2268 3.4208 False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 21 Position of Joint left_elbow_roll_joint -2.0943 2.0943 False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 22 Position of Joint right_shoulder_pitch_joint -2.9671 2.7925 False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 23 Position of Joint right_shoulder_roll_joint -2.2515 1.5882 False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 24 Position of Joint right_shoulder_yaw_joint -2.618 2.618 False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 25 Position of Joint right_elbow_pitch_joint -0.2268 3.4208 False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 26 Position of Joint right_elbow_roll_joint -2.0943 2.0943 False 1 Angle [rad]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 27 Velocity of Joint pelvis_tx -inf inf False 1 Velocity [m/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 28 Velocity of Joint pelvis_tz -inf inf False 1 Velocity [m/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 29 Velocity of Joint pelvis_ty -inf inf False 1 Velocity [m/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 30 Velocity of Joint pelvis_tilt -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 31 Velocity of Joint pelvis_list -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 32 Velocity of Joint pelvis_rotation -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 33 Velocity of Joint left_hip_pitch_joint -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 34 Velocity of Joint left_hip_roll_joint -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 35 Velocity of Joint left_hip_yaw_joint -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 36 Velocity of Joint left_knee_joint -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 37 Velocity of Joint left_ankle_pitch_joint -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 38 Velocity of Joint left_ankle_roll_joint -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 39 Velocity of Joint right_hip_pitch_joint -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 40 Velocity of Joint right_hip_roll_joint -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 41 Velocity of Joint right_hip_yaw_joint -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 42 Velocity of Joint right_knee_joint -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 43 Velocity of Joint right_ankle_pitch_joint -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 44 Velocity of Joint right_ankle_roll_joint -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 45 Velocity of Joint torso_joint -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 46 Velocity of Joint left_shoulder_pitch_joint -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 47 Velocity of Joint left_shoulder_roll_joint -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 48 Velocity of Joint left_shoulder_yaw_joint -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 49 Velocity of Joint left_elbow_pitch_joint -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 50 Velocity of Joint left_elbow_roll_joint -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 51 Velocity of Joint right_shoulder_pitch_joint -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 52 Velocity of Joint right_shoulder_roll_joint -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 53 Velocity of Joint right_shoulder_yaw_joint -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 54 Velocity of Joint right_elbow_pitch_joint -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 55 Velocity of Joint right_elbow_roll_joint -inf inf False 1 Angular Velocity [rad/s]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 56 3D linear Forces between Right Foot and Floor 0.0 inf True 3 Force [N]
+ ----- --------------------------------------------- -------- ------ -------- --- ------------------------
+ 59 3D linear Forces between Left Foot and Floor 0.0 inf True 3 Force [N]
+ ===== ============================================= ======== ====== ======== === ========================
Action Space
------------
| The action space has the following properties *by default* (i.e., only actions with Disabled == False):
- | :code:`(min=-1, max=1, dim=11, dtype=float32)`
-
- Some actions are **disabled by default**, but can be turned on. The detailed action space is:
-
- ===== ======================== =========== =========== ========
- Index Name in XML Control Min Control Max Disabled
- ===== ======================== =========== =========== ========
- 0 back_bkz_actuator -1.0 1.0 False
- ----- ------------------------ ----------- ----------- --------
- 1 l_arm_shy_actuator -1.0 1.0 True
- ----- ------------------------ ----------- ----------- --------
- 2 l_arm_shx_actuator -1.0 1.0 True
- ----- ------------------------ ----------- ----------- --------
- 3 l_arm_shz_actuator -1.0 1.0 True
- ----- ------------------------ ----------- ----------- --------
- 4 left_elbow_actuator -1.0 1.0 True
- ----- ------------------------ ----------- ----------- --------
- 5 r_arm_shy_actuator -1.0 1.0 True
- ----- ------------------------ ----------- ----------- --------
- 6 r_arm_shx_actuator -1.0 1.0 True
- ----- ------------------------ ----------- ----------- --------
- 7 r_arm_shz_actuator -1.0 1.0 True
- ----- ------------------------ ----------- ----------- --------
- 8 right_elbow_actuator -1.0 1.0 True
- ----- ------------------------ ----------- ----------- --------
- 9 hip_flexion_r_actuator -1.0 1.0 False
- ----- ------------------------ ----------- ----------- --------
- 10 hip_adduction_r_actuator -1.0 1.0 False
- ----- ------------------------ ----------- ----------- --------
- 11 hip_rotation_r_actuator -1.0 1.0 False
- ----- ------------------------ ----------- ----------- --------
- 12 knee_angle_r_actuator -1.0 1.0 False
- ----- ------------------------ ----------- ----------- --------
- 13 ankle_angle_r_actuator -1.0 1.0 False
- ----- ------------------------ ----------- ----------- --------
- 14 hip_flexion_l_actuator -1.0 1.0 False
- ----- ------------------------ ----------- ----------- --------
- 15 hip_adduction_l_actuator -1.0 1.0 False
- ----- ------------------------ ----------- ----------- --------
- 16 hip_rotation_l_actuator -1.0 1.0 False
- ----- ------------------------ ----------- ----------- --------
- 17 knee_angle_l_actuator -1.0 1.0 False
- ----- ------------------------ ----------- ----------- --------
- 18 ankle_angle_l_actuator -1.0 1.0 False
- ===== ======================== =========== =========== ========
-
+ | :code:`(min=-1, max=1, dim=23, dtype=float32)`
+
+ ===== ========================== =========== =========== ========
+ Index Name in XML Control Min Control Max Disabled
+ ===== ========================== =========== =========== ========
+ 0 left_hip_pitch_joint -1.0 1.0 False
+ ----- -------------------------- ----------- ----------- --------
+ 1 left_hip_roll_joint -1.0 1.0 False
+ ----- -------------------------- ----------- ----------- --------
+ 2 left_hip_yaw_joint -1.0 1.0 False
+ ----- -------------------------- ----------- ----------- --------
+ 3 left_knee_joint -1.0 1.0 False
+ ----- -------------------------- ----------- ----------- --------
+ 4 left_ankle_pitch_joint -1.0 1.0 False
+ ----- -------------------------- ----------- ----------- --------
+ 5 left_ankle_roll_joint -1.0 1.0 False
+ ----- -------------------------- ----------- ----------- --------
+ 6 right_hip_pitch_joint -1.0 1.0 False
+ ----- -------------------------- ----------- ----------- --------
+ 7 right_hip_roll_joint -1.0 1.0 False
+ ----- -------------------------- ----------- ----------- --------
+ 8 right_hip_yaw_joint -1.0 1.0 False
+ ----- -------------------------- ----------- ----------- --------
+ 9 right_knee_joint -1.0 1.0 False
+ ----- -------------------------- ----------- ----------- --------
+ 10 right_ankle_pitch_joint -1.0 1.0 False
+ ----- -------------------------- ----------- ----------- --------
+ 11 right_ankle_roll_joint -1.0 1.0 False
+ ----- -------------------------- ----------- ----------- --------
+ 12 torso_joint -1.0 1.0 False
+ ----- -------------------------- ----------- ----------- --------
+ 13 left_shoulder_pitch_joint -1.0 1.0 False
+ ----- -------------------------- ----------- ----------- --------
+ 14 left_shoulder_roll_joint -1.0 1.0 False
+ ----- -------------------------- ----------- ----------- --------
+ 15 left_shoulder_yaw_joint -1.0 1.0 False
+ ----- -------------------------- ----------- ----------- --------
+ 16 left_elbow_pitch_joint -1.0 1.0 False
+ ----- -------------------------- ----------- ----------- --------
+ 17 left_elbow_roll_joint -1.0 1.0 False
+ ----- -------------------------- ----------- ----------- --------
+ 18 right_shoulder_pitch_joint -1.0 1.0 False
+ ----- -------------------------- ----------- ----------- --------
+ 19 right_shoulder_roll_joint -1.0 1.0 False
+ ----- -------------------------- ----------- ----------- --------
+ 20 right_shoulder_yaw_joint -1.0 1.0 False
+ ----- -------------------------- ----------- ----------- --------
+ 21 right_elbow_pitch_joint -1.0 1.0 False
+ ----- -------------------------- ----------- ----------- --------
+ 22 right_elbow_roll_joint -1.0 1.0 False
+ ===== ========================== =========== =========== ========
Rewards
--------
@@ -224,7 +243,7 @@ class UnitreeG1(BaseRobotHumanoid):
valid_task_confs = ValidTaskConf(tasks=["walk", "run"],
data_types=["real"])
- def __init__(self, disable_arms=True, disable_back_joint=False, **kwargs):
+ def __init__(self, disable_arms=False, disable_back_joint=False, **kwargs):
"""
Constructor.
@@ -235,9 +254,12 @@ def __init__(self, disable_arms=True, disable_back_joint=False, **kwargs):
self._hold_weight = False # no weights supported with this envs
- action_spec = self._get_action_specification(xml_handle)
+ # save xml_handle
+ self._xml_handles = [xml_handle]
+
+ action_spec = self._get_action_specification()
- observation_spec = self._get_observation_specification(xml_handle)
+ observation_spec = self._get_observation_specification()
collision_groups = [("floor", ["floor"]),
("right_foot_1", ["right_foot_1_col"]),
@@ -272,26 +294,30 @@ def __init__(self, disable_arms=True, disable_back_joint=False, **kwargs):
def _get_ground_forces(self):
"""
- Returns the ground forces (np.array). By default, 4 ground force sensors are used.
- Environments that use more or less have to override this function.
+ Calculates the ground forces (np.array). Per foot, the ground reaction force (linear --> 3D) is measured at
+ 4 points resulting in a 4*3*2=24 dimensional force vector.
+
+ Returns:
+ The ground forces (np.array) vector of all foots.
"""
- grf = np.concatenate([self._get_collision_force("floor", "right_foot_1_col")[:3],
- self._get_collision_force("floor", "right_foot_2_col")[:3],
- self._get_collision_force("floor", "right_foot_3_col")[:3],
- self._get_collision_force("floor", "right_foot_4_col")[:3],
- self._get_collision_force("floor", "left_foot_1_col")[:3],
- self._get_collision_force("floor", "left_foot_2_col")[:3],
- self._get_collision_force("floor", "left_foot_3_col")[:3],
- self._get_collision_force("floor", "left_foot_4_col")[:3]])
+ grf = np.concatenate([self._get_collision_force("floor", "right_foot_1")[:3],
+ self._get_collision_force("floor", "right_foot_2")[:3],
+ self._get_collision_force("floor", "right_foot_3")[:3],
+ self._get_collision_force("floor", "right_foot_4")[:3],
+ self._get_collision_force("floor", "left_foot_1")[:3],
+ self._get_collision_force("floor", "left_foot_2")[:3],
+ self._get_collision_force("floor", "left_foot_3")[:3],
+ self._get_collision_force("floor", "left_foot_4")[:3]])
return grf
@staticmethod
def _get_grf_size():
"""
- Returns the size of the ground force vector.
+ Returns:
+ The size of the ground force vector.
"""
@@ -369,19 +395,24 @@ def _has_fallen(self, obs, return_err_msg=False):
@staticmethod
def generate(task="walk", dataset_type="real", **kwargs):
"""
- Returns an environment corresponding to the specified task.
+ Generates an environment corresponding to the specified task.
Args:
- task (str): Main task to solve. Either "walk", "run" or "carry". The latter is walking while carrying
- an unknown weight, which makes the task partially observable.
- dataset_type (str): "real" or "perfect". "real" uses real motion capture data as the
- reference trajectory. This data does not perfectly match the kinematics
- and dynamics of this environment, hence it is more challenging. "perfect" uses
- a perfect dataset.
+ task (str): Main task to solve. Either "walk", "run" or "carry". The latter is walking while carrying
+ an unknown weight, which makes the task partially observable.
+ dataset_type (str): "real" or "perfect". "real" uses real motion capture data as the
+ reference trajectory. This data does not perfectly match the kinematics
+ and dynamics of this environment, hence it is more challenging. "perfect" uses
+ a perfect dataset.
+
+ Returns:
+ Returns an environment corresponding to the specified task.
"""
+
check_validity_task_mode_dataset(UnitreeG1.__name__, task, None, dataset_type,
*UnitreeG1.valid_task_confs.get_all())
+
if dataset_type == "real":
if task == "run":
path = "datasets/humanoids/real/05-run_UnitreeG1.npz"
@@ -403,6 +434,7 @@ def _reorient_arms(xml_handle):
Modified Mujoco XML handle.
"""
+
# modify the arm orientation
left_shoulder_pitch_link = xml_handle.find("body", "left_shoulder_pitch_link")
left_shoulder_pitch_link.quat = [1.0, 0.25, 0.1, 0.0]
@@ -415,8 +447,7 @@ def _reorient_arms(xml_handle):
return xml_handle
- @staticmethod
- def _get_observation_specification(xml_handle):
+ def _get_observation_specification(self):
"""
Getter for the observation space specification.
@@ -425,15 +456,15 @@ def _get_observation_specification(xml_handle):
space entry.
"""
+
observation_spec = []
for prefix in ["q_", "dq_"]:
- for j in xml_handle.find_all("joint"):
+ for j in self.xml_handle.find_all("joint"):
obs_type = ObservationType.JOINT_POS if prefix == "q_" else ObservationType.JOINT_VEL
observation_spec.append((prefix + j.name, j.name, obs_type))
return observation_spec
- @staticmethod
- def _get_action_specification(xml_handle):
+ def _get_action_specification(self):
"""
Getter for the action space specification.
@@ -442,8 +473,9 @@ def _get_action_specification(xml_handle):
space entry.
"""
+
action_spec = []
- actuators = xml_handle.find_all("actuator")
+ actuators = self.xml_handle.find_all("actuator")
for actuator in actuators:
action_spec.append(actuator.name)
return action_spec
diff --git a/loco_mujoco/environments/humanoids/unitreeH1.py b/loco_mujoco/environments/humanoids/unitreeH1.py
index d511119..aa4e693 100644
--- a/loco_mujoco/environments/humanoids/unitreeH1.py
+++ b/loco_mujoco/environments/humanoids/unitreeH1.py
@@ -16,7 +16,7 @@ class UnitreeH1(BaseRobotHumanoid):
Description
------------
- Mujoco simulation of the Unitree H1 robot. Optionally, the H1 can carry
+ Mujoco environment of the Unitree H1 robot. Optionally, the H1 can carry
a weight. This environment can be partially observable by hiding
some of the state space entries from the policy using a state mask.
Hidable entries are "positions", "velocities", "foot_forces",
diff --git a/loco_mujoco/environments/quadrupeds/unitreeA1.py b/loco_mujoco/environments/quadrupeds/unitreeA1.py
index 44f3b3e..61283b0 100644
--- a/loco_mujoco/environments/quadrupeds/unitreeA1.py
+++ b/loco_mujoco/environments/quadrupeds/unitreeA1.py
@@ -24,7 +24,7 @@ class UnitreeA1(LocoEnv):
Description
------------
- Mujoco simulation of Unitree A1 model.
+ Mujoco environment of Unitree A1 model.
Tasks
-----------------
diff --git a/loco_mujoco/utils/dataset.py b/loco_mujoco/utils/dataset.py
index bd32780..d289471 100644
--- a/loco_mujoco/utils/dataset.py
+++ b/loco_mujoco/utils/dataset.py
@@ -31,10 +31,10 @@ def download_real_datasets():
dataset_path_humanoid = dataset_path / "humanoids/real"
dataset_path_humanoid_str = str(dataset_path_humanoid)
os.makedirs(dataset_path_humanoid_str, exist_ok=True)
- humanoid_url = "https://zenodo.org/records/11113527/files/humanoid_datasets_v0.2.1.zip?download=1"
+ humanoid_url = "https://zenodo.org/records/11217638/files/humanoid_datasets_v0.3.0.zip?download=1"
wget.download(humanoid_url, out=dataset_path_humanoid_str)
print("\n")
- file_name = "humanoid_datasets_v0.2.1.zip"
+ file_name = "humanoid_datasets_v0.3.0.zip"
file_path = str(dataset_path_humanoid / file_name)
with zipfile.ZipFile(file_path, "r") as zip_ref:
zip_ref.extractall(dataset_path_humanoid_str)
@@ -44,10 +44,10 @@ def download_real_datasets():
dataset_path_quadrupeds = dataset_path / "quadrupeds/real"
dataset_path_quadrupeds_str = str(dataset_path_quadrupeds)
os.makedirs(dataset_path_quadrupeds_str, exist_ok=True)
- quadruped_url = "https://zenodo.org/records/11113527/files/quadruped_datasets_v0.2.1.zip?download=1"
+ quadruped_url = "https://zenodo.org/records/11217638/files/quadruped_datasets_v0.3.0.zip?download=1"
wget.download(quadruped_url, out=dataset_path_quadrupeds_str)
print("\n")
- file_name = "quadruped_datasets_v0.2.1.zip"
+ file_name = "quadruped_datasets_v0.3.0.zip"
file_path = str(dataset_path_quadrupeds / file_name)
with zipfile.ZipFile(file_path, "r") as zip_ref:
zip_ref.extractall(dataset_path_quadrupeds_str)
@@ -65,10 +65,10 @@ def download_perfect_datasets():
dataset_path_humanoid = dataset_path / "humanoids/perfect"
dataset_path_humanoid_str = str(dataset_path_humanoid)
os.makedirs(dataset_path_humanoid_str, exist_ok=True)
- humanoid_url = "https://zenodo.org/records/11113527/files/humanoid_datasets_perfect_v0.2.1.zip?download=1"
+ humanoid_url = "https://zenodo.org/records/11217638/files/humanoid_datasets_perfect_v0.3.0.zip?download=1"
wget.download(humanoid_url, out=dataset_path_humanoid_str)
print("\n")
- file_name = "humanoid_datasets_perfect_v0.2.1.zip"
+ file_name = "humanoid_datasets_perfect_v0.3.0.zip"
file_path = str(dataset_path_humanoid / file_name)
with zipfile.ZipFile(file_path, "r") as zip_ref:
zip_ref.extractall(dataset_path_humanoid_str)
@@ -79,10 +79,10 @@ def download_perfect_datasets():
dataset_path_quadrupeds = dataset_path / "quadrupeds/perfect"
dataset_path_quadrupeds_str = str(dataset_path_quadrupeds)
os.makedirs(dataset_path_quadrupeds_str, exist_ok=True)
- quadruped_url = "https://zenodo.org/records/11113527/files/quadruped_datasets_perfect_v0.2.1.zip?download=1"
+ quadruped_url = "https://zenodo.org/records/11217638/files/quadruped_datasets_perfect_v0.3.0.zip?download=1"
wget.download(quadruped_url, out=dataset_path_quadrupeds_str)
print("\n")
- file_name = "quadruped_datasets_perfect_v0.2.1.zip"
+ file_name = "quadruped_datasets_perfect_v0.3.0.zip"
file_path = str(dataset_path_quadrupeds / file_name)
with zipfile.ZipFile(file_path, "r") as zip_ref:
zip_ref.extractall(dataset_path_quadrupeds_str)
diff --git a/requirements.txt b/requirements.txt
index 33af046..707cef9 100644
--- a/requirements.txt
+++ b/requirements.txt
@@ -1,7 +1,7 @@
mushroom-rl>=1.10.0
numpy
scipy
-mujoco>=2.3.6
+mujoco==2.3.7
gymnasium
dm_control
pyyaml
diff --git a/tests/test_datasets/HumanoidMuscle4Ages.run.1.real.npy b/tests/test_datasets/HumanoidMuscle4Ages.run.1.real.npy
index 71130ed..d6c0665 100644
Binary files a/tests/test_datasets/HumanoidMuscle4Ages.run.1.real.npy and b/tests/test_datasets/HumanoidMuscle4Ages.run.1.real.npy differ
diff --git a/tests/test_datasets/HumanoidMuscle4Ages.run.2.real.npy b/tests/test_datasets/HumanoidMuscle4Ages.run.2.real.npy
index 7600130..535345f 100644
Binary files a/tests/test_datasets/HumanoidMuscle4Ages.run.2.real.npy and b/tests/test_datasets/HumanoidMuscle4Ages.run.2.real.npy differ
diff --git a/tests/test_datasets/HumanoidMuscle4Ages.run.3.real.npy b/tests/test_datasets/HumanoidMuscle4Ages.run.3.real.npy
index 089a08b..4c912ee 100644
Binary files a/tests/test_datasets/HumanoidMuscle4Ages.run.3.real.npy and b/tests/test_datasets/HumanoidMuscle4Ages.run.3.real.npy differ
diff --git a/tests/test_datasets/HumanoidMuscle4Ages.run.4.real.npy b/tests/test_datasets/HumanoidMuscle4Ages.run.4.real.npy
index 60e6531..42b1eb3 100644
Binary files a/tests/test_datasets/HumanoidMuscle4Ages.run.4.real.npy and b/tests/test_datasets/HumanoidMuscle4Ages.run.4.real.npy differ
diff --git a/tests/test_datasets/HumanoidMuscle4Ages.walk.1.real.npy b/tests/test_datasets/HumanoidMuscle4Ages.walk.1.real.npy
index 52c78d1..4d6bf2d 100644
Binary files a/tests/test_datasets/HumanoidMuscle4Ages.walk.1.real.npy and b/tests/test_datasets/HumanoidMuscle4Ages.walk.1.real.npy differ
diff --git a/tests/test_datasets/HumanoidMuscle4Ages.walk.2.real.npy b/tests/test_datasets/HumanoidMuscle4Ages.walk.2.real.npy
index 5ebce3f..ca21984 100644
Binary files a/tests/test_datasets/HumanoidMuscle4Ages.walk.2.real.npy and b/tests/test_datasets/HumanoidMuscle4Ages.walk.2.real.npy differ
diff --git a/tests/test_datasets/HumanoidMuscle4Ages.walk.3.real.npy b/tests/test_datasets/HumanoidMuscle4Ages.walk.3.real.npy
index 4fdcce6..604824f 100644
Binary files a/tests/test_datasets/HumanoidMuscle4Ages.walk.3.real.npy and b/tests/test_datasets/HumanoidMuscle4Ages.walk.3.real.npy differ
diff --git a/tests/test_datasets/HumanoidMuscle4Ages.walk.4.real.npy b/tests/test_datasets/HumanoidMuscle4Ages.walk.4.real.npy
index b7792e1..cc6729b 100644
Binary files a/tests/test_datasets/HumanoidMuscle4Ages.walk.4.real.npy and b/tests/test_datasets/HumanoidMuscle4Ages.walk.4.real.npy differ
diff --git a/tests/test_datasets/HumanoidTorque4Ages.run.1.real.npy b/tests/test_datasets/HumanoidTorque4Ages.run.1.real.npy
index f6b7e03..c7e2ed0 100644
Binary files a/tests/test_datasets/HumanoidTorque4Ages.run.1.real.npy and b/tests/test_datasets/HumanoidTorque4Ages.run.1.real.npy differ
diff --git a/tests/test_datasets/HumanoidTorque4Ages.run.2.real.npy b/tests/test_datasets/HumanoidTorque4Ages.run.2.real.npy
index dba8562..9742235 100644
Binary files a/tests/test_datasets/HumanoidTorque4Ages.run.2.real.npy and b/tests/test_datasets/HumanoidTorque4Ages.run.2.real.npy differ
diff --git a/tests/test_datasets/HumanoidTorque4Ages.run.3.real.npy b/tests/test_datasets/HumanoidTorque4Ages.run.3.real.npy
index 798ca98..ed9c4ab 100644
Binary files a/tests/test_datasets/HumanoidTorque4Ages.run.3.real.npy and b/tests/test_datasets/HumanoidTorque4Ages.run.3.real.npy differ
diff --git a/tests/test_datasets/HumanoidTorque4Ages.run.4.real.npy b/tests/test_datasets/HumanoidTorque4Ages.run.4.real.npy
index 89e29b3..6ac49aa 100644
Binary files a/tests/test_datasets/HumanoidTorque4Ages.run.4.real.npy and b/tests/test_datasets/HumanoidTorque4Ages.run.4.real.npy differ
diff --git a/tests/test_datasets/HumanoidTorque4Ages.walk.1.real.npy b/tests/test_datasets/HumanoidTorque4Ages.walk.1.real.npy
index e2347c6..48666a3 100644
Binary files a/tests/test_datasets/HumanoidTorque4Ages.walk.1.real.npy and b/tests/test_datasets/HumanoidTorque4Ages.walk.1.real.npy differ
diff --git a/tests/test_datasets/HumanoidTorque4Ages.walk.2.real.npy b/tests/test_datasets/HumanoidTorque4Ages.walk.2.real.npy
index 5e5e4f9..be5fec0 100644
Binary files a/tests/test_datasets/HumanoidTorque4Ages.walk.2.real.npy and b/tests/test_datasets/HumanoidTorque4Ages.walk.2.real.npy differ
diff --git a/tests/test_datasets/HumanoidTorque4Ages.walk.3.real.npy b/tests/test_datasets/HumanoidTorque4Ages.walk.3.real.npy
index 7753dec..e149c3d 100644
Binary files a/tests/test_datasets/HumanoidTorque4Ages.walk.3.real.npy and b/tests/test_datasets/HumanoidTorque4Ages.walk.3.real.npy differ
diff --git a/tests/test_datasets/HumanoidTorque4Ages.walk.4.real.npy b/tests/test_datasets/HumanoidTorque4Ages.walk.4.real.npy
index 55bec91..baff9ee 100644
Binary files a/tests/test_datasets/HumanoidTorque4Ages.walk.4.real.npy and b/tests/test_datasets/HumanoidTorque4Ages.walk.4.real.npy differ
diff --git a/tests/test_datasets/UnitreeA1.hard.real.npy b/tests/test_datasets/UnitreeA1.hard.real.npy
index 1a032c4..5ff5ea3 100644
Binary files a/tests/test_datasets/UnitreeA1.hard.real.npy and b/tests/test_datasets/UnitreeA1.hard.real.npy differ
diff --git a/tests/test_datasets/UnitreeA1.simple.real.npy b/tests/test_datasets/UnitreeA1.simple.real.npy
index 407806e..d798f71 100644
Binary files a/tests/test_datasets/UnitreeA1.simple.real.npy and b/tests/test_datasets/UnitreeA1.simple.real.npy differ
diff --git a/tests/test_datasets/UnitreeG1.run.real.npy b/tests/test_datasets/UnitreeG1.run.real.npy
new file mode 100644
index 0000000..072b80b
Binary files /dev/null and b/tests/test_datasets/UnitreeG1.run.real.npy differ
diff --git a/tests/test_datasets/UnitreeG1.walk.real.npy b/tests/test_datasets/UnitreeG1.walk.real.npy
new file mode 100644
index 0000000..30e2965
Binary files /dev/null and b/tests/test_datasets/UnitreeG1.walk.real.npy differ
diff --git a/tests/test_datasets/UnitreeH1.carry.real.npy b/tests/test_datasets/UnitreeH1.carry.real.npy
index 2f95de3..4a9a714 100644
Binary files a/tests/test_datasets/UnitreeH1.carry.real.npy and b/tests/test_datasets/UnitreeH1.carry.real.npy differ
diff --git a/tests/test_datasets/UnitreeH1.run.real.npy b/tests/test_datasets/UnitreeH1.run.real.npy
index 734004f..5a5f81c 100644
Binary files a/tests/test_datasets/UnitreeH1.run.real.npy and b/tests/test_datasets/UnitreeH1.run.real.npy differ
diff --git a/tests/test_datasets/UnitreeH1.walk.real.npy b/tests/test_datasets/UnitreeH1.walk.real.npy
index 2a8f023..9acb5d3 100644
Binary files a/tests/test_datasets/UnitreeH1.walk.real.npy and b/tests/test_datasets/UnitreeH1.walk.real.npy differ
diff --git a/tests/test_environments.py b/tests/test_environments.py
index 8fbc0fc..19c8b39 100644
--- a/tests/test_environments.py
+++ b/tests/test_environments.py
@@ -90,12 +90,8 @@ def test_all_environments():
test_dataset = np.load(dataset_path)
- if not np.allclose(dataset, test_dataset):
- return False
- if not np.allclose(dataset_gym, test_dataset):
- return False
-
- return True
+ assert np.allclose(dataset, test_dataset)
+ assert np.allclose(dataset_gym, test_dataset)
def test_replays():
@@ -126,8 +122,3 @@ def test_replays():
task_env = gym.make("LocoMujoco", env_name=task_name, debug=True)
task_env.play_trajectory(n_episodes=N_EPISODES_REP, n_steps_per_episode=N_STEPS_REP, render=False)
- return True
-
-
-if __name__ == "__main__":
- test_all_environments()