From 8260a7010ab05ba3ff8e5710afc1f0849c0d283b Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Fri, 29 Mar 2024 14:04:44 +0100 Subject: [PATCH] Add xarm as package --- envs/sim_pusht/pyproject.toml | 3 + lerobot/common/envs/pusht/env.py | 8 +- lerobot/common/envs/simxarm/env.py | 8 +- .../common/envs/simxarm/simxarm/__init__.py | 166 ------------------ .../envs/simxarm/simxarm/tasks/__init__.py | 0 .../simxarm/simxarm/tasks/assets/lift.xml | 53 ------ .../simxarm/tasks/assets/mesh/base_link.stl | 3 - .../simxarm/tasks/assets/mesh/block_inner.stl | 3 - .../tasks/assets/mesh/block_inner2.stl | 3 - .../simxarm/tasks/assets/mesh/block_outer.stl | 3 - .../simxarm/tasks/assets/mesh/left_finger.stl | 3 - .../tasks/assets/mesh/left_inner_knuckle.stl | 3 - .../tasks/assets/mesh/left_outer_knuckle.stl | 3 - .../simxarm/tasks/assets/mesh/link1.stl | 3 - .../simxarm/tasks/assets/mesh/link2.stl | 3 - .../simxarm/tasks/assets/mesh/link3.stl | 3 - .../simxarm/tasks/assets/mesh/link4.stl | 3 - .../simxarm/tasks/assets/mesh/link5.stl | 3 - .../simxarm/tasks/assets/mesh/link6.stl | 3 - .../simxarm/tasks/assets/mesh/link7.stl | 3 - .../simxarm/tasks/assets/mesh/link_base.stl | 3 - .../tasks/assets/mesh/right_finger.stl | 3 - .../tasks/assets/mesh/right_inner_knuckle.stl | 3 - .../tasks/assets/mesh/right_outer_knuckle.stl | 3 - .../simxarm/tasks/assets/peg_in_box.xml | 74 -------- .../simxarm/simxarm/tasks/assets/push.xml | 54 ------ .../simxarm/simxarm/tasks/assets/reach.xml | 48 ----- .../simxarm/simxarm/tasks/assets/shared.xml | 51 ------ .../simxarm/simxarm/tasks/assets/xarm.xml | 88 ---------- .../common/envs/simxarm/simxarm/tasks/base.py | 145 --------------- .../common/envs/simxarm/simxarm/tasks/lift.py | 100 ----------- .../envs/simxarm/simxarm/tasks/mocap.py | 67 ------- .../envs/simxarm/simxarm/tasks/peg_in_box.py | 86 --------- .../common/envs/simxarm/simxarm/tasks/push.py | 78 -------- .../envs/simxarm/simxarm/tasks/reach.py | 44 ----- poetry.lock | 19 +- pyproject.toml | 5 +- 37 files changed, 39 insertions(+), 1112 deletions(-) delete mode 100644 lerobot/common/envs/simxarm/simxarm/__init__.py delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/__init__.py delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/assets/lift.xml delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/base_link.stl delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/block_inner.stl delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/block_inner2.stl delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/block_outer.stl delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/left_finger.stl delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/left_inner_knuckle.stl delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/left_outer_knuckle.stl delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link1.stl delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link2.stl delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link3.stl delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link4.stl delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link5.stl delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link6.stl delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link7.stl delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link_base.stl delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/right_finger.stl delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/right_inner_knuckle.stl delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/right_outer_knuckle.stl delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/assets/peg_in_box.xml delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/assets/push.xml delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/assets/reach.xml delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/assets/shared.xml delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/assets/xarm.xml delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/base.py delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/lift.py delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/mocap.py delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/peg_in_box.py delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/push.py delete mode 100644 lerobot/common/envs/simxarm/simxarm/tasks/reach.py diff --git a/envs/sim_pusht/pyproject.toml b/envs/sim_pusht/pyproject.toml index 2d269e05..3e2668cd 100644 --- a/envs/sim_pusht/pyproject.toml +++ b/envs/sim_pusht/pyproject.toml @@ -7,6 +7,7 @@ authors = [ ] maintainers = [ "Alexander Soare ", + "Quentin Gallouédec ", "Simon Alibert ", ] readme = "README.md" @@ -20,6 +21,7 @@ classifiers=[ ] packages = [{include = "pusht"}] + [tool.poetry.dependencies] python = "^3.10" gymnasium = "^0.29.1" @@ -29,6 +31,7 @@ pymunk = "^6.6.0" shapely = "^2.0.3" scikit-image = "^0.22.0" + [build-system] requires = ["poetry-core"] build-backend = "poetry.core.masonry.api" diff --git a/lerobot/common/envs/pusht/env.py b/lerobot/common/envs/pusht/env.py index 96811ca5..0b206f12 100644 --- a/lerobot/common/envs/pusht/env.py +++ b/lerobot/common/envs/pusht/env.py @@ -19,6 +19,7 @@ from lerobot.common.envs.abstract import AbstractEnv from lerobot.common.utils import set_global_seed _has_gym = importlib.util.find_spec("gymnasium") is not None +_has_pusht = importlib.util.find_spec("pusht") is not None class PushtEnv(AbstractEnv): @@ -56,9 +57,14 @@ class PushtEnv(AbstractEnv): # TODO(rcadene) (PushTEnv is similar to PushTImageEnv, but without the image rendering, it's faster to iterate on) # from lerobot.common.envs.pusht.pusht_env import PushTEnv - if not self.from_pixels: raise NotImplementedError("Use PushTEnv, instead of PushTImageEnv") + + if not _has_pusht: + raise ImportError( + "Cannot import pusht env. Please install it with `python -m pip install 'lerobot[pusht]'`" + ) + from pusht.pusht_image_env import PushTImageEnv self._env = PushTImageEnv(render_size=self.image_size) diff --git a/lerobot/common/envs/simxarm/env.py b/lerobot/common/envs/simxarm/env.py index b81bf499..4f0b62ec 100644 --- a/lerobot/common/envs/simxarm/env.py +++ b/lerobot/common/envs/simxarm/env.py @@ -21,6 +21,7 @@ from lerobot.common.utils import set_global_seed MAX_NUM_ACTIONS = 4 _has_gym = importlib.util.find_spec("gymnasium") is not None +_has_xarm = importlib.util.find_spec("xarm") is not None class SimxarmEnv(AbstractEnv): @@ -57,7 +58,12 @@ class SimxarmEnv(AbstractEnv): import gymnasium - from lerobot.common.envs.simxarm.simxarm import TASKS + if not _has_xarm: + raise ImportError( + "Cannot import xarm env. Please install it with `python -m pip install 'lerobot[xarm]'`" + ) + + from xarm import TASKS if self.task not in TASKS: raise ValueError(f"Unknown task {self.task}. Must be one of {list(TASKS.keys())}") diff --git a/lerobot/common/envs/simxarm/simxarm/__init__.py b/lerobot/common/envs/simxarm/simxarm/__init__.py deleted file mode 100644 index 903d6042..00000000 --- a/lerobot/common/envs/simxarm/simxarm/__init__.py +++ /dev/null @@ -1,166 +0,0 @@ -from collections import OrderedDict, deque - -import gymnasium as gym -import numpy as np -from gymnasium.wrappers import TimeLimit - -from lerobot.common.envs.simxarm.simxarm.tasks.base import Base as Base -from lerobot.common.envs.simxarm.simxarm.tasks.lift import Lift -from lerobot.common.envs.simxarm.simxarm.tasks.peg_in_box import PegInBox -from lerobot.common.envs.simxarm.simxarm.tasks.push import Push -from lerobot.common.envs.simxarm.simxarm.tasks.reach import Reach - -TASKS = OrderedDict( - ( - ( - "reach", - { - "env": Reach, - "action_space": "xyz", - "episode_length": 50, - "description": "Reach a target location with the end effector", - }, - ), - ( - "push", - { - "env": Push, - "action_space": "xyz", - "episode_length": 50, - "description": "Push a cube to a target location", - }, - ), - ( - "peg_in_box", - { - "env": PegInBox, - "action_space": "xyz", - "episode_length": 50, - "description": "Insert a peg into a box", - }, - ), - ( - "lift", - { - "env": Lift, - "action_space": "xyzw", - "episode_length": 50, - "description": "Lift a cube above a height threshold", - }, - ), - ) -) - - -class SimXarmWrapper(gym.Wrapper): - """ - A wrapper for the SimXarm environments. This wrapper is used to - convert the action and observation spaces to the correct format. - """ - - def __init__(self, env, task, obs_mode, image_size, action_repeat, frame_stack=1, channel_last=False): - super().__init__(env) - self._env = env - self.obs_mode = obs_mode - self.image_size = image_size - self.action_repeat = action_repeat - self.frame_stack = frame_stack - self._frames = deque([], maxlen=frame_stack) - self.channel_last = channel_last - self._max_episode_steps = task["episode_length"] // action_repeat - - image_shape = ( - (image_size, image_size, 3 * frame_stack) - if channel_last - else (3 * frame_stack, image_size, image_size) - ) - if obs_mode == "state": - self.observation_space = env.observation_space["observation"] - elif obs_mode == "rgb": - self.observation_space = gym.spaces.Box(low=0, high=255, shape=image_shape, dtype=np.uint8) - elif obs_mode == "all": - self.observation_space = gym.spaces.Dict( - state=gym.spaces.Box(low=-np.inf, high=np.inf, shape=(4,), dtype=np.float32), - rgb=gym.spaces.Box(low=0, high=255, shape=image_shape, dtype=np.uint8), - ) - else: - raise ValueError(f"Unknown obs_mode {obs_mode}. Must be one of [rgb, all, state]") - self.action_space = gym.spaces.Box(low=-1.0, high=1.0, shape=(len(task["action_space"]),)) - self.action_padding = np.zeros(4 - len(task["action_space"]), dtype=np.float32) - if "w" not in task["action_space"]: - self.action_padding[-1] = 1.0 - - def _render_obs(self): - obs = self.render(mode="rgb_array", width=self.image_size, height=self.image_size) - if not self.channel_last: - obs = obs.transpose(2, 0, 1) - return obs.copy() - - def _update_frames(self, reset=False): - pixels = self._render_obs() - self._frames.append(pixels) - if reset: - for _ in range(1, self.frame_stack): - self._frames.append(pixels) - assert len(self._frames) == self.frame_stack - - def transform_obs(self, obs, reset=False): - if self.obs_mode == "state": - return obs["observation"] - elif self.obs_mode == "rgb": - self._update_frames(reset=reset) - rgb_obs = np.concatenate(list(self._frames), axis=-1 if self.channel_last else 0) - return rgb_obs - elif self.obs_mode == "all": - self._update_frames(reset=reset) - rgb_obs = np.concatenate(list(self._frames), axis=-1 if self.channel_last else 0) - return OrderedDict((("rgb", rgb_obs), ("state", self.robot_state))) - else: - raise ValueError(f"Unknown obs_mode {self.obs_mode}. Must be one of [rgb, all, state]") - - def reset(self): - return self.transform_obs(self._env.reset(), reset=True) - - def step(self, action): - action = np.concatenate([action, self.action_padding]) - reward = 0.0 - for _ in range(self.action_repeat): - obs, r, done, info = self._env.step(action) - reward += r - return self.transform_obs(obs), reward, done, info - - def render(self, mode="rgb_array", width=384, height=384, **kwargs): - return self._env.render(mode, width=width, height=height) - - @property - def state(self): - return self._env.robot_state - - -def make(task, obs_mode="state", image_size=84, action_repeat=1, frame_stack=1, channel_last=False, seed=0): - """ - Create a new environment. - Args: - task (str): The task to create an environment for. Must be one of: - - 'reach' - - 'push' - - 'peg-in-box' - - 'lift' - obs_mode (str): The observation mode to use. Must be one of: - - 'state': Only state observations - - 'rgb': RGB images - - 'all': RGB images and state observations - image_size (int): The size of the image observations - action_repeat (int): The number of times to repeat the action - seed (int): The random seed to use - Returns: - gym.Env: The environment - """ - if task not in TASKS: - raise ValueError(f"Unknown task {task}. Must be one of {list(TASKS.keys())}") - env = TASKS[task]["env"]() - env = TimeLimit(env, TASKS[task]["episode_length"]) - env = SimXarmWrapper(env, TASKS[task], obs_mode, image_size, action_repeat, frame_stack, channel_last) - env.seed(seed) - - return env diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/__init__.py b/lerobot/common/envs/simxarm/simxarm/tasks/__init__.py deleted file mode 100644 index e69de29b..00000000 diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/assets/lift.xml b/lerobot/common/envs/simxarm/simxarm/tasks/assets/lift.xml deleted file mode 100644 index 92231f92..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/assets/lift.xml +++ /dev/null @@ -1,53 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/base_link.stl b/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/base_link.stl deleted file mode 100644 index f1f52955..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/base_link.stl +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:21fb81ae7fba19e3c6b2d2ca60c8051712ba273357287eb5a397d92d61c7a736 -size 1211434 diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/block_inner.stl b/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/block_inner.stl deleted file mode 100644 index 6cb88945..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/block_inner.stl +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:be68ce180d11630a667a5f37f4dffcc3feebe4217d4bb3912c813b6d9ca3ec66 -size 3284 diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/block_inner2.stl b/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/block_inner2.stl deleted file mode 100644 index dab55ef5..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/block_inner2.stl +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:2c6448552bf6b1c4f17334d686a5320ce051bcdfe31431edf69303d8a570d1de -size 3284 diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/block_outer.stl b/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/block_outer.stl deleted file mode 100644 index 21cf11fa..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/block_outer.stl +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:748b9e197e6521914f18d1f6383a36f211136b3f33f2ad2a8c11b9f921c2cf86 -size 6284 diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/left_finger.stl b/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/left_finger.stl deleted file mode 100644 index 6bf4e502..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/left_finger.stl +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:a44756eb72f9c214cb37e61dc209cd7073fdff3e4271a7423476ef6fd090d2d4 -size 242684 diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/left_inner_knuckle.stl b/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/left_inner_knuckle.stl deleted file mode 100644 index 817c7e1d..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/left_inner_knuckle.stl +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:e8e48692ad26837bb3d6a97582c89784d09948fc09bfe4e5a59017859ff04dac -size 366284 diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/left_outer_knuckle.stl b/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/left_outer_knuckle.stl deleted file mode 100644 index 010c0f3b..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/left_outer_knuckle.stl +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:501665812b08d67e764390db781e839adc6896a9540301d60adf606f57648921 -size 22284 diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link1.stl b/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link1.stl deleted file mode 100644 index f2b676f2..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link1.stl +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:34b541122df84d2ef5fcb91b715eb19659dc15ad8d44a191dde481f780265636 -size 184184 diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link2.stl b/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link2.stl deleted file mode 100644 index bf93580c..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link2.stl +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:61e641cd47c169ecef779683332e00e4914db729bf02dfb61bfbe69351827455 -size 225584 diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link3.stl b/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link3.stl deleted file mode 100644 index d316d233..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link3.stl +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:9e2798e7946dd70046c95455d5ba96392d0b54a6069caba91dc4ca66e1379b42 -size 237084 diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link4.stl b/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link4.stl deleted file mode 100644 index f6d5fe94..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link4.stl +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:c757fee95f873191a0633c355c07a360032960771cabbd7593a6cdb0f1ffb089 -size 243684 diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link5.stl b/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link5.stl deleted file mode 100644 index e037b8b9..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link5.stl +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:715ad5787c5dab57589937fd47289882707b5e1eb997e340d567785b02f4ec90 -size 229084 diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link6.stl b/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link6.stl deleted file mode 100644 index 198c5300..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link6.stl +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:85b320aa420497827223d16d492bba8de091173374e361396fc7a5dad7bdb0cb -size 399384 diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link7.stl b/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link7.stl deleted file mode 100644 index ce9a39ac..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link7.stl +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:97115d848fbf802cb770cd9be639ae2af993103b9d9bbb0c50c943c738a36f18 -size 231684 diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link_base.stl b/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link_base.stl deleted file mode 100644 index 110b9531..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/link_base.stl +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:f6fcbc18258090eb56c21cfb17baa5ae43abc98b1958cd366f3a73b9898fc7f0 -size 2106184 diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/right_finger.stl b/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/right_finger.stl deleted file mode 100644 index 03f26e9a..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/right_finger.stl +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:c5dee87c7f37baf554b8456ebfe0b3e8ed0b22b8938bd1add6505c2ad6d32c7d -size 242684 diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/right_inner_knuckle.stl b/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/right_inner_knuckle.stl deleted file mode 100644 index 8586f344..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/right_inner_knuckle.stl +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:b41dd2c2c550281bf78d7cc6fa117b14786700e5c453560a0cb5fd6dfa0ffb3e -size 366284 diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/right_outer_knuckle.stl b/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/right_outer_knuckle.stl deleted file mode 100644 index ae7afc25..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/assets/mesh/right_outer_knuckle.stl +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:75ca1107d0a42a0f03802a9a49cab48419b31851ee8935f8f1ca06be1c1c91e8 -size 22284 diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/assets/peg_in_box.xml b/lerobot/common/envs/simxarm/simxarm/tasks/assets/peg_in_box.xml deleted file mode 100644 index 0f85459f..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/assets/peg_in_box.xml +++ /dev/null @@ -1,74 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/assets/push.xml b/lerobot/common/envs/simxarm/simxarm/tasks/assets/push.xml deleted file mode 100644 index 42a78c8a..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/assets/push.xml +++ /dev/null @@ -1,54 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/assets/reach.xml b/lerobot/common/envs/simxarm/simxarm/tasks/assets/reach.xml deleted file mode 100644 index ded6d209..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/assets/reach.xml +++ /dev/null @@ -1,48 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/assets/shared.xml b/lerobot/common/envs/simxarm/simxarm/tasks/assets/shared.xml deleted file mode 100644 index ee56f8f0..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/assets/shared.xml +++ /dev/null @@ -1,51 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/assets/xarm.xml b/lerobot/common/envs/simxarm/simxarm/tasks/assets/xarm.xml deleted file mode 100644 index 023474d6..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/assets/xarm.xml +++ /dev/null @@ -1,88 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/base.py b/lerobot/common/envs/simxarm/simxarm/tasks/base.py deleted file mode 100644 index b937b290..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/base.py +++ /dev/null @@ -1,145 +0,0 @@ -import os - -import mujoco -import numpy as np -from gymnasium_robotics.envs import robot_env - -from lerobot.common.envs.simxarm.simxarm.tasks import mocap - - -class Base(robot_env.MujocoRobotEnv): - """ - Superclass for all simxarm environments. - Args: - xml_name (str): name of the xml environment file - gripper_rotation (list): initial rotation of the gripper (given as a quaternion) - """ - - def __init__(self, xml_name, gripper_rotation=None): - if gripper_rotation is None: - gripper_rotation = [0, 1, 0, 0] - self.gripper_rotation = np.array(gripper_rotation, dtype=np.float32) - self.center_of_table = np.array([1.655, 0.3, 0.63625]) - self.max_z = 1.2 - self.min_z = 0.2 - super().__init__( - model_path=os.path.join(os.path.dirname(__file__), "assets", xml_name + ".xml"), - n_substeps=20, - n_actions=4, - initial_qpos={}, - ) - - @property - def dt(self): - return self.n_substeps * self.model.opt.timestep - - @property - def eef(self): - return self._utils.get_site_xpos(self.model, self.data, "grasp") - - @property - def obj(self): - return self._utils.get_site_xpos(self.model, self.data, "object_site") - - @property - def robot_state(self): - gripper_angle = self._utils.get_joint_qpos(self.model, self.data, "right_outer_knuckle_joint") - return np.concatenate([self.eef, gripper_angle]) - - def is_success(self): - return NotImplementedError() - - def get_reward(self): - raise NotImplementedError() - - def _sample_goal(self): - raise NotImplementedError() - - def get_obs(self): - return self._get_obs() - - def _step_callback(self): - self._mujoco.mj_forward(self.model, self.data) - - def _limit_gripper(self, gripper_pos, pos_ctrl): - if gripper_pos[0] > self.center_of_table[0] - 0.105 + 0.15: - pos_ctrl[0] = min(pos_ctrl[0], 0) - if gripper_pos[0] < self.center_of_table[0] - 0.105 - 0.3: - pos_ctrl[0] = max(pos_ctrl[0], 0) - if gripper_pos[1] > self.center_of_table[1] + 0.3: - pos_ctrl[1] = min(pos_ctrl[1], 0) - if gripper_pos[1] < self.center_of_table[1] - 0.3: - pos_ctrl[1] = max(pos_ctrl[1], 0) - if gripper_pos[2] > self.max_z: - pos_ctrl[2] = min(pos_ctrl[2], 0) - if gripper_pos[2] < self.min_z: - pos_ctrl[2] = max(pos_ctrl[2], 0) - return pos_ctrl - - def _apply_action(self, action): - assert action.shape == (4,) - action = action.copy() - pos_ctrl, gripper_ctrl = action[:3], action[3] - pos_ctrl = self._limit_gripper( - self._utils.get_site_xpos(self.model, self.data, "grasp"), pos_ctrl - ) * (1 / self.n_substeps) - gripper_ctrl = np.array([gripper_ctrl, gripper_ctrl]) - mocap.apply_action( - self.model, - self._model_names, - self.data, - np.concatenate([pos_ctrl, self.gripper_rotation, gripper_ctrl]), - ) - - def _render_callback(self): - self._mujoco.mj_forward(self.model, self.data) - - def _reset_sim(self): - self.data.time = self.initial_time - self.data.qpos[:] = np.copy(self.initial_qpos) - self.data.qvel[:] = np.copy(self.initial_qvel) - self._sample_goal() - self._mujoco.mj_step(self.model, self.data, nstep=10) - return True - - def _set_gripper(self, gripper_pos, gripper_rotation): - self._utils.set_mocap_pos(self.model, self.data, "robot0:mocap", gripper_pos) - self._utils.set_mocap_quat(self.model, self.data, "robot0:mocap", gripper_rotation) - self._utils.set_joint_qpos(self.model, self.data, "right_outer_knuckle_joint", 0) - self.data.qpos[10] = 0.0 - self.data.qpos[12] = 0.0 - - def _env_setup(self, initial_qpos): - for name, value in initial_qpos.items(): - self.data.set_joint_qpos(name, value) - mocap.reset(self.model, self.data) - mujoco.mj_forward(self.model, self.data) - self._sample_goal() - mujoco.mj_forward(self.model, self.data) - - def reset(self): - self._reset_sim() - return self._get_obs() - - def step(self, action): - assert action.shape == (4,) - assert self.action_space.contains(action), "{!r} ({}) invalid".format(action, type(action)) - self._apply_action(action) - self._mujoco.mj_step(self.model, self.data, nstep=2) - self._step_callback() - obs = self._get_obs() - reward = self.get_reward() - done = False - info = {"is_success": self.is_success(), "success": self.is_success()} - return obs, reward, done, info - - def render(self, mode="rgb_array", width=384, height=384): - self._render_callback() - # HACK - self.model.vis.global_.offwidth = width - self.model.vis.global_.offheight = height - return self.mujoco_renderer.render(mode) - - def close(self): - if self.mujoco_renderer is not None: - self.mujoco_renderer.close() diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/lift.py b/lerobot/common/envs/simxarm/simxarm/tasks/lift.py deleted file mode 100644 index 0b11196c..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/lift.py +++ /dev/null @@ -1,100 +0,0 @@ -import numpy as np - -from lerobot.common.envs.simxarm.simxarm import Base - - -class Lift(Base): - def __init__(self): - self._z_threshold = 0.15 - super().__init__("lift") - - @property - def z_target(self): - return self._init_z + self._z_threshold - - def is_success(self): - return self.obj[2] >= self.z_target - - def get_reward(self): - reach_dist = np.linalg.norm(self.obj - self.eef) - reach_dist_xy = np.linalg.norm(self.obj[:-1] - self.eef[:-1]) - pick_completed = self.obj[2] >= (self.z_target - 0.01) - obj_dropped = (self.obj[2] < (self._init_z + 0.005)) and (reach_dist > 0.02) - - # Reach - if reach_dist < 0.05: - reach_reward = -reach_dist + max(self._action[-1], 0) / 50 - elif reach_dist_xy < 0.05: - reach_reward = -reach_dist - else: - z_bonus = np.linalg.norm(np.linalg.norm(self.obj[-1] - self.eef[-1])) - reach_reward = -reach_dist - 2 * z_bonus - - # Pick - if pick_completed and not obj_dropped: - pick_reward = self.z_target - elif (reach_dist < 0.1) and (self.obj[2] > (self._init_z + 0.005)): - pick_reward = min(self.z_target, self.obj[2]) - else: - pick_reward = 0 - - return reach_reward / 100 + pick_reward - - def _get_obs(self): - eef_velp = self._utils.get_site_xvelp(self.model, self.data, "grasp") * self.dt - gripper_angle = self._utils.get_joint_qpos(self.model, self.data, "right_outer_knuckle_joint") - eef = self.eef - self.center_of_table - - obj = self.obj - self.center_of_table - obj_rot = self._utils.get_joint_qpos(self.model, self.data, "object_joint0")[-4:] - obj_velp = self._utils.get_site_xvelp(self.model, self.data, "object_site") * self.dt - obj_velr = self._utils.get_site_xvelr(self.model, self.data, "object_site") * self.dt - - obs = np.concatenate( - [ - eef, - eef_velp, - obj, - obj_rot, - obj_velp, - obj_velr, - eef - obj, - np.array( - [ - np.linalg.norm(eef - obj), - np.linalg.norm(eef[:-1] - obj[:-1]), - self.z_target, - self.z_target - obj[-1], - self.z_target - eef[-1], - ] - ), - gripper_angle, - ], - axis=0, - ) - return {"observation": obs, "state": eef, "achieved_goal": eef, "desired_goal": eef} - - def _sample_goal(self): - # Gripper - gripper_pos = np.array([1.280, 0.295, 0.735]) + self.np_random.uniform(-0.05, 0.05, size=3) - super()._set_gripper(gripper_pos, self.gripper_rotation) - - # Object - object_pos = self.center_of_table - np.array([0.15, 0.10, 0.07]) - object_pos[0] += self.np_random.uniform(-0.05, 0.05, size=1) - object_pos[1] += self.np_random.uniform(-0.05, 0.05, size=1) - object_qpos = self._utils.get_joint_qpos(self.model, self.data, "object_joint0") - object_qpos[:3] = object_pos - self._utils.set_joint_qpos(self.model, self.data, "object_joint0", object_qpos) - self._init_z = object_pos[2] - - # Goal - return object_pos + np.array([0, 0, self._z_threshold]) - - def reset(self): - self._action = np.zeros(4) - return super().reset() - - def step(self, action): - self._action = action.copy() - return super().step(action) diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/mocap.py b/lerobot/common/envs/simxarm/simxarm/tasks/mocap.py deleted file mode 100644 index 4295bf19..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/mocap.py +++ /dev/null @@ -1,67 +0,0 @@ -# import mujoco_py -import mujoco -import numpy as np - - -def apply_action(model, model_names, data, action): - if model.nmocap > 0: - pos_action, gripper_action = np.split(action, (model.nmocap * 7,)) - if data.ctrl is not None: - for i in range(gripper_action.shape[0]): - data.ctrl[i] = gripper_action[i] - pos_action = pos_action.reshape(model.nmocap, 7) - pos_delta, quat_delta = pos_action[:, :3], pos_action[:, 3:] - reset_mocap2body_xpos(model, model_names, data) - data.mocap_pos[:] = data.mocap_pos + pos_delta - data.mocap_quat[:] = data.mocap_quat + quat_delta - - -def reset(model, data): - if model.nmocap > 0 and model.eq_data is not None: - for i in range(model.eq_data.shape[0]): - # if sim.model.eq_type[i] == mujoco_py.const.EQ_WELD: - if model.eq_type[i] == mujoco.mjtEq.mjEQ_WELD: - # model.eq_data[i, :] = np.array([0., 0., 0., 1., 0., 0., 0.]) - model.eq_data[i, :] = np.array( - [ - 0.0, - 0.0, - 0.0, - 1.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - 0.0, - ] - ) - # sim.forward() - mujoco.mj_forward(model, data) - - -def reset_mocap2body_xpos(model, model_names, data): - if model.eq_type is None or model.eq_obj1id is None or model.eq_obj2id is None: - return - - # For all weld constraints - for eq_type, obj1_id, obj2_id in zip(model.eq_type, model.eq_obj1id, model.eq_obj2id, strict=False): - # if eq_type != mujoco_py.const.EQ_WELD: - if eq_type != mujoco.mjtEq.mjEQ_WELD: - continue - # body2 = model.body_id2name(obj2_id) - body2 = model_names.body_id2name[obj2_id] - if body2 == "B0" or body2 == "B9" or body2 == "B1": - continue - mocap_id = model.body_mocapid[obj1_id] - if mocap_id != -1: - # obj1 is the mocap, obj2 is the welded body - body_idx = obj2_id - else: - # obj2 is the mocap, obj1 is the welded body - mocap_id = model.body_mocapid[obj2_id] - body_idx = obj1_id - assert mocap_id != -1 - data.mocap_pos[mocap_id][:] = data.xpos[body_idx] - data.mocap_quat[mocap_id][:] = data.xquat[body_idx] diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/peg_in_box.py b/lerobot/common/envs/simxarm/simxarm/tasks/peg_in_box.py deleted file mode 100644 index 42e41520..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/peg_in_box.py +++ /dev/null @@ -1,86 +0,0 @@ -import numpy as np - -from lerobot.common.envs.simxarm.simxarm import Base - - -class PegInBox(Base): - def __init__(self): - super().__init__("peg_in_box") - - def _reset_sim(self): - self._act_magnitude = 0 - super()._reset_sim() - for _ in range(10): - self._apply_action(np.array([0, 0, 0, 1], dtype=np.float32)) - self.sim.step() - - @property - def box(self): - return self.sim.data.get_site_xpos("box_site") - - def is_success(self): - return np.linalg.norm(self.obj - self.box) <= 0.05 - - def get_reward(self): - dist_xy = np.linalg.norm(self.obj[:2] - self.box[:2]) - dist_xyz = np.linalg.norm(self.obj - self.box) - return float(dist_xy <= 0.045) * (2 - 6 * dist_xyz) - 0.2 * np.square(self._act_magnitude) - dist_xy - - def _get_obs(self): - eef_velp = self.sim.data.get_site_xvelp("grasp") * self.dt - gripper_angle = self.sim.data.get_joint_qpos("right_outer_knuckle_joint") - eef, box = self.eef - self.center_of_table, self.box - self.center_of_table - - obj = self.obj - self.center_of_table - obj_rot = self.sim.data.get_joint_qpos("object_joint0")[-4:] - obj_velp = self.sim.data.get_site_xvelp("object_site") * self.dt - obj_velr = self.sim.data.get_site_xvelr("object_site") * self.dt - - obs = np.concatenate( - [ - eef, - eef_velp, - box, - obj, - obj_rot, - obj_velp, - obj_velr, - eef - box, - eef - obj, - obj - box, - np.array( - [ - np.linalg.norm(eef - box), - np.linalg.norm(eef - obj), - np.linalg.norm(obj - box), - gripper_angle, - ] - ), - ], - axis=0, - ) - return {"observation": obs, "state": eef, "achieved_goal": eef, "desired_goal": box} - - def _sample_goal(self): - # Gripper - gripper_pos = np.array([1.280, 0.295, 0.9]) + self.np_random.uniform(-0.05, 0.05, size=3) - super()._set_gripper(gripper_pos, self.gripper_rotation) - - # Object - object_pos = gripper_pos - np.array([0, 0, 0.06]) + self.np_random.uniform(-0.005, 0.005, size=3) - object_qpos = self.sim.data.get_joint_qpos("object_joint0") - object_qpos[:3] = object_pos - self.sim.data.set_joint_qpos("object_joint0", object_qpos) - - # Box - box_pos = np.array([1.61, 0.18, 0.58]) - box_pos[:2] += self.np_random.uniform(-0.11, 0.11, size=2) - box_qpos = self.sim.data.get_joint_qpos("box_joint0") - box_qpos[:3] = box_pos - self.sim.data.set_joint_qpos("box_joint0", box_qpos) - - return self.box - - def step(self, action): - self._act_magnitude = np.linalg.norm(action[:3]) - return super().step(action) diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/push.py b/lerobot/common/envs/simxarm/simxarm/tasks/push.py deleted file mode 100644 index 36c4a550..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/push.py +++ /dev/null @@ -1,78 +0,0 @@ -import numpy as np - -from lerobot.common.envs.simxarm.simxarm import Base - - -class Push(Base): - def __init__(self): - super().__init__("push") - - def _reset_sim(self): - self._act_magnitude = 0 - super()._reset_sim() - - def is_success(self): - return np.linalg.norm(self.obj - self.goal) <= 0.05 - - def get_reward(self): - dist = np.linalg.norm(self.obj - self.goal) - penalty = self._act_magnitude**2 - return -(dist + 0.15 * penalty) - - def _get_obs(self): - eef_velp = self.sim.data.get_site_xvelp("grasp") * self.dt - gripper_angle = self.sim.data.get_joint_qpos("right_outer_knuckle_joint") - eef, goal = self.eef - self.center_of_table, self.goal - self.center_of_table - - obj = self.obj - self.center_of_table - obj_rot = self.sim.data.get_joint_qpos("object_joint0")[-4:] - obj_velp = self.sim.data.get_site_xvelp("object_site") * self.dt - obj_velr = self.sim.data.get_site_xvelr("object_site") * self.dt - - obs = np.concatenate( - [ - eef, - eef_velp, - goal, - obj, - obj_rot, - obj_velp, - obj_velr, - eef - goal, - eef - obj, - obj - goal, - np.array( - [ - np.linalg.norm(eef - goal), - np.linalg.norm(eef - obj), - np.linalg.norm(obj - goal), - gripper_angle, - ] - ), - ], - axis=0, - ) - return {"observation": obs, "state": eef, "achieved_goal": eef, "desired_goal": goal} - - def _sample_goal(self): - # Gripper - gripper_pos = np.array([1.280, 0.295, 0.735]) + self.np_random.uniform(-0.05, 0.05, size=3) - super()._set_gripper(gripper_pos, self.gripper_rotation) - - # Object - object_pos = self.center_of_table - np.array([0.25, 0, 0.07]) - object_pos[0] += self.np_random.uniform(-0.08, 0.08, size=1) - object_pos[1] += self.np_random.uniform(-0.08, 0.08, size=1) - object_qpos = self.sim.data.get_joint_qpos("object_joint0") - object_qpos[:3] = object_pos - self.sim.data.set_joint_qpos("object_joint0", object_qpos) - - # Goal - self.goal = np.array([1.600, 0.200, 0.545]) - self.goal[:2] += self.np_random.uniform(-0.1, 0.1, size=2) - self.sim.model.site_pos[self.sim.model.site_name2id("target0")] = self.goal - return self.goal - - def step(self, action): - self._act_magnitude = np.linalg.norm(action[:3]) - return super().step(action) diff --git a/lerobot/common/envs/simxarm/simxarm/tasks/reach.py b/lerobot/common/envs/simxarm/simxarm/tasks/reach.py deleted file mode 100644 index 941a586f..00000000 --- a/lerobot/common/envs/simxarm/simxarm/tasks/reach.py +++ /dev/null @@ -1,44 +0,0 @@ -import numpy as np - -from lerobot.common.envs.simxarm.simxarm import Base - - -class Reach(Base): - def __init__(self): - super().__init__("reach") - - def _reset_sim(self): - self._act_magnitude = 0 - super()._reset_sim() - - def is_success(self): - return np.linalg.norm(self.eef - self.goal) <= 0.05 - - def get_reward(self): - dist = np.linalg.norm(self.eef - self.goal) - penalty = self._act_magnitude**2 - return -(dist + 0.15 * penalty) - - def _get_obs(self): - eef_velp = self.sim.data.get_site_xvelp("grasp") * self.dt - gripper_angle = self.sim.data.get_joint_qpos("right_outer_knuckle_joint") - eef, goal = self.eef - self.center_of_table, self.goal - self.center_of_table - obs = np.concatenate( - [eef, eef_velp, goal, eef - goal, np.array([np.linalg.norm(eef - goal), gripper_angle])], axis=0 - ) - return {"observation": obs, "state": eef, "achieved_goal": eef, "desired_goal": goal} - - def _sample_goal(self): - # Gripper - gripper_pos = np.array([1.280, 0.295, 0.735]) + self.np_random.uniform(-0.05, 0.05, size=3) - super()._set_gripper(gripper_pos, self.gripper_rotation) - - # Goal - self.goal = np.array([1.550, 0.287, 0.580]) - self.goal[:2] += self.np_random.uniform(-0.125, 0.125, size=2) - self.sim.model.site_pos[self.sim.model.site_name2id("target0")] = self.goal - return self.goal - - def step(self, action): - self._act_magnitude = np.linalg.norm(action[:3]) - return super().step(action) diff --git a/poetry.lock b/poetry.lock index b05cdc96..a1a59b69 100644 --- a/poetry.lock +++ b/poetry.lock @@ -3115,6 +3115,22 @@ pymunk = ">=6.6.0,<7.0.0" scikit-image = ">=0.22.0,<0.23.0" shapely = ">=2.0.3,<3.0.0" +[[package]] +name = "sim-xarm" +version = "0.1.0" +description = "xArm environment for LeRobot" +optional = true +python-versions = "<4.0,>=3.10" +files = [ + {file = "sim_xarm-0.1.0-py3-none-any.whl", hash = "sha256:2771ca0e8d775dc7d9ccb3360e7fcf42507c5d4791525692e409f53ff5c83eaa"}, + {file = "sim_xarm-0.1.0.tar.gz", hash = "sha256:90342394369ab37636a8c41a995ba20f1dac79c50563b1b1e4b38eeffbc5588d"}, +] + +[package.dependencies] +gymnasium = ">=0.29.1,<0.30.0" +gymnasium-robotics = ">=1.2.4,<2.0.0" +mujoco = ">=2.3.7,<3.0.0" + [[package]] name = "six" version = "1.16.0" @@ -3607,8 +3623,9 @@ testing = ["big-O", "jaraco.functools", "jaraco.itertools", "more-itertools", "p [extras] pusht = ["sim-pusht"] +xarm = ["sim-xarm"] [metadata] lock-version = "2.0" python-versions = "^3.10" -content-hash = "91dcb5cc851e0a348bfa36801e6cd260391a851623f0949575a5a19ca014d75c" +content-hash = "0ac21898262a0d5410340f822b4aa3ae4580348ebb2bc58dbd351f46a0feedbd" diff --git a/pyproject.toml b/pyproject.toml index cfda20c7..bcf27b05 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -7,6 +7,7 @@ authors = [ ] maintainers = [ "Alexander Soare ", + "Quentin Gallouédec ", "Simon Alibert ", ] repository = "https://github.com/Cadene/lerobot" @@ -57,10 +58,12 @@ gymnasium-robotics = "^1.2.4" gymnasium = "^0.29.1" cmake = "^3.29.0.1" sim-pusht = { version = "^0.1.0", optional = true} +sim-xarm = { version = "^0.1.0", optional = true} [tool.poetry.extras] pusht = ["sim-pusht"] +xarm = ["sim-xarm"] [tool.poetry.group.dev.dependencies] @@ -106,7 +109,7 @@ select = ["E4", "E7", "E9", "F", "I", "N", "B", "C4", "SIM"] ignore-init-module-imports = true [tool.ruff.lint.isort] -known-first-party = ["pusht"] +known-first-party = ["pusht", "xarm"] [tool.poetry-dynamic-versioning] enable = true