diff --git a/.gitignore b/.gitignore index 09269dd..e0404f1 100644 --- a/.gitignore +++ b/.gitignore @@ -1,3 +1,176 @@ *.model venv -.vscode + +# Ignore poetry.lock to allow for ROCm-based torch installations +poetry.lock + + +### Python +# Byte-compiled / optimized / DLL files +__pycache__/ +*.py[cod] +*$py.class + +# C extensions +*.so + +# Distribution / packaging +.Python +build/ +develop-eggs/ +dist/ +downloads/ +eggs/ +.eggs/ +lib/ +lib64/ +parts/ +sdist/ +var/ +wheels/ +share/python-wheels/ +*.egg-info/ +.installed.cfg +*.egg +MANIFEST + +# PyInstaller +# Usually these files are written by a python script from a template +# before PyInstaller builds the exe, so as to inject date/other infos into it. +*.manifest +*.spec + +# Installer logs +pip-log.txt +pip-delete-this-directory.txt + +# Unit test / coverage reports +htmlcov/ +.tox/ +.nox/ +.coverage +.coverage.* +.cache +nosetests.xml +coverage.xml +*.cover +*.py,cover +.hypothesis/ +.pytest_cache/ +cover/ + +# Translations +*.mo +*.pot + +# Django stuff: +*.log +local_settings.py +db.sqlite3 +db.sqlite3-journal + +# Flask stuff: +instance/ +.webassets-cache + +# Scrapy stuff: +.scrapy + +# Sphinx documentation +docs/_build/ + +# PyBuilder +.pybuilder/ +target/ + +# Jupyter Notebook +.ipynb_checkpoints + +# IPython +profile_default/ +ipython_config.py + +# pyenv +# For a library or package, you might want to ignore these files since the code is +# intended to run in multiple environments; otherwise, check them in: +# .python-version + +# pipenv +# According to pypa/pipenv#598, it is recommended to include Pipfile.lock in version control. +# However, in case of collaboration, if having platform-specific dependencies or dependencies +# having no cross-platform support, pipenv may install dependencies that don't work, or not +# install all needed dependencies. +#Pipfile.lock + +# UV +# Similar to Pipfile.lock, it is generally recommended to include uv.lock in version control. +# This is especially recommended for binary packages to ensure reproducibility, and is more +# commonly ignored for libraries. +#uv.lock + +# poetry +# Similar to Pipfile.lock, it is generally recommended to include poetry.lock in version control. +# This is especially recommended for binary packages to ensure reproducibility, and is more +# commonly ignored for libraries. +# https://python-poetry.org/docs/basic-usage/#commit-your-poetrylock-file-to-version-control +#poetry.lock + +# pdm +# Similar to Pipfile.lock, it is generally recommended to include pdm.lock in version control. +#pdm.lock +# pdm stores project-wide configurations in .pdm.toml, but it is recommended to not include it +# in version control. +# https://pdm.fming.dev/latest/usage/project/#working-with-version-control +.pdm.toml +.pdm-python +.pdm-build/ + +# PEP 582; used by e.g. github.com/David-OConnor/pyflow and github.com/pdm-project/pdm +__pypackages__/ + +# Celery stuff +celerybeat-schedule +celerybeat.pid + +# SageMath parsed files +*.sage.py + +# Environments +.env +.venv +env/ +venv/ +ENV/ +env.bak/ +venv.bak/ + +# Spyder project settings +.spyderproject +.spyproject + +# Rope project settings +.ropeproject + +# mkdocs documentation +/site + +# mypy +.mypy_cache/ +.dmypy.json +dmypy.json + +# Pyre type checker +.pyre/ + +# pytype static type analyzer +.pytype/ + +# Cython debug symbols +cython_debug/ + +# PyCharm +# JetBrains specific template is maintained in a separate JetBrains.gitignore that can +# be found at https://github.com/github/gitignore/blob/main/Global/JetBrains.gitignore +# and can be added to the global gitignore or merged into this file. For a more nuclear +# option (not recommended) you can uncomment the following to ignore the entire idea folder. +#.idea/ diff --git a/.vscode/launch.json b/.vscode/launch.json new file mode 100644 index 0000000..15f652c --- /dev/null +++ b/.vscode/launch.json @@ -0,0 +1,12 @@ +{ + "version": "0.2.0", + "configurations": [ + { + "name": "drone", + "type": "debugpy", + "request": "launch", + "program": "drone/main.py", + "console": "integratedTerminal" + } + ] +} \ No newline at end of file diff --git a/Makefile b/Makefile new file mode 100644 index 0000000..99750e9 --- /dev/null +++ b/Makefile @@ -0,0 +1,15 @@ +default: run +.PHONY: default run + +setup: + sudo apt install pipx + pipx ensurepath + pipx install poetry + poetry install --without rocm + poetry update --without rocm + +build: + poetry build + +run: + poetry run python drone/main.py diff --git a/README.md b/README.md new file mode 100644 index 0000000..e69de29 diff --git a/drone/gym_multirotor/__init__.py b/drone/gym_multirotor/__init__.py new file mode 100644 index 0000000..e1fbb8e --- /dev/null +++ b/drone/gym_multirotor/__init__.py @@ -0,0 +1,23 @@ +from gymnasium.envs.registration import register +from gym_multirotor import envs # noqa: F401 +from gym_multirotor.envs import mujoco # noqa: F401 +from gym_multirotor.envs.mujoco import * # noqa: F403 + + +# Quadrotors with Plus(+)-configuration +register( + id="QuadrotorPlusHoverEnv-v0", + entry_point="gym_multirotor.envs.mujoco.quadrotor_plus_hover:QuadrotorPlusHoverEnv", +) + + +register( + id="TiltrotorPlus8DofHoverEnv-v0", + entry_point="gym_multirotor.envs.mujoco.tiltrotor_plus_hover:TiltrotorPlus8DofHoverEnv", +) + +# Quadrotor with X-configuration +register( + id="QuadrotorXHoverEnv-v0", + entry_point="gym_multirotor.envs.mujoco.quadrotor_x_hover:QuadrotorXHoverEnv", +) diff --git a/gym_multirotor/envs/__init__.py b/drone/gym_multirotor/envs/__init__.py similarity index 100% rename from gym_multirotor/envs/__init__.py rename to drone/gym_multirotor/envs/__init__.py diff --git a/drone/gym_multirotor/envs/mujoco/__init__.py b/drone/gym_multirotor/envs/mujoco/__init__.py new file mode 100644 index 0000000..5a805dc --- /dev/null +++ b/drone/gym_multirotor/envs/mujoco/__init__.py @@ -0,0 +1 @@ +from gym_multirotor.envs.mujoco.base_env import UAVBaseEnv # noqa: F401 diff --git a/gym_multirotor/envs/mujoco/assets/quadrotor_plus.xml b/drone/gym_multirotor/envs/mujoco/assets/quadrotor_plus.xml similarity index 100% rename from gym_multirotor/envs/mujoco/assets/quadrotor_plus.xml rename to drone/gym_multirotor/envs/mujoco/assets/quadrotor_plus.xml diff --git a/gym_multirotor/envs/mujoco/assets/quadrotor_x.xml b/drone/gym_multirotor/envs/mujoco/assets/quadrotor_x.xml similarity index 100% rename from gym_multirotor/envs/mujoco/assets/quadrotor_x.xml rename to drone/gym_multirotor/envs/mujoco/assets/quadrotor_x.xml diff --git a/gym_multirotor/envs/mujoco/assets/tiltrotor_plus_hover.xml b/drone/gym_multirotor/envs/mujoco/assets/tiltrotor_plus_hover.xml similarity index 100% rename from gym_multirotor/envs/mujoco/assets/tiltrotor_plus_hover.xml rename to drone/gym_multirotor/envs/mujoco/assets/tiltrotor_plus_hover.xml diff --git a/gym_multirotor/envs/mujoco/base_env.py b/drone/gym_multirotor/envs/mujoco/base_env.py similarity index 88% rename from gym_multirotor/envs/mujoco/base_env.py rename to drone/gym_multirotor/envs/mujoco/base_env.py index 76073d7..e2d3b16 100644 --- a/gym_multirotor/envs/mujoco/base_env.py +++ b/drone/gym_multirotor/envs/mujoco/base_env.py @@ -2,9 +2,9 @@ import math from abc import ABC import numpy as np -from gym import spaces -from gym import utils -from gym.envs.mujoco import MujocoEnv +from gymnasium import spaces +from gymnasium import utils +from gymnasium.envs.mujoco import MujocoEnv from gym_multirotor import utils as multirotor_utils @@ -43,36 +43,36 @@ class UAVBaseEnv(MujocoEnv, utils.EzPickle, ABC): obs_avel_index = np.arange(15, 18) action_index_thrust = np.arange(0, 4) render_mode = "human" - metadata = { - "render_modes": ["human", "rgb_array", "depth_array"], - "render_fps": 20 - } - - def __init__(self, - xml_name="quadrotor_plus.xml", - frame_skip=5, - error_tolerance=0.05, - max_time_steps=1000, - randomize_reset=True, - disorient=True, - sample_SO3=True, - observation_noise_std=0.1, - reduce_heading_error=True, - env_bounding_box=3, - init_max_vel=0.5, - init_max_angular_vel=0.1*math.pi, - init_max_attitude=math.pi/3.0, - bonus_to_reach_goal=15.0, - max_reward_for_velocity_towards_goal=2.0, - position_reward_constant=5.0, - orientation_reward_constant=0.02, - linear_velocity_reward_constant=0.01, - angular_velocity_reward_constant=0.001, - action_reward_constant=0.0025, - reward_for_staying_alive=5.0, - reward_scaling_coefficient=1.0, - ): - xml_path = os.path.abspath(os.path.join(os.path.dirname(__file__), "assets", xml_name)) + metadata = {"render_modes": ["human", "rgb_array", "depth_array"], "render_fps": 20} + + def __init__( + self, + xml_name="quadrotor_plus.xml", + frame_skip=5, + error_tolerance=0.05, + max_time_steps=1000, + randomize_reset=True, + disorient=True, + sample_SO3=True, + observation_noise_std=0.1, + reduce_heading_error=True, + env_bounding_box=3, + init_max_vel=0.5, + init_max_angular_vel=0.1 * math.pi, + init_max_attitude=math.pi / 3.0, + bonus_to_reach_goal=15.0, + max_reward_for_velocity_towards_goal=2.0, + position_reward_constant=5.0, + orientation_reward_constant=0.02, + linear_velocity_reward_constant=0.01, + angular_velocity_reward_constant=0.001, + action_reward_constant=0.0025, + reward_for_staying_alive=5.0, + reward_scaling_coefficient=1.0, + ): + xml_path = os.path.abspath( + os.path.join(os.path.dirname(__file__), "assets", xml_name) + ) self.error_tolerance = error_tolerance """float: Error tolerance. Default is `0.05`.""" @@ -189,18 +189,21 @@ def __init__(self, """numpy.ndarray: Buffer to keep record of orientation from mujoco. Stores current orientation quaternion. """ - self.current_policy_action = np.array([-1, -1, -1, -1.]) + self.current_policy_action = np.array([-1, -1, -1, -1.0]) """numpy.ndarray: Buffer to hold current action input from policy to the environment. Stores the action vector scaled between (-1., 1.) """ self.desired_position = np.array([0, 0, 3.0]) """numpy.ndarray: Desired position of the system. Goal of the RL agent.""" - self._time = 0 # initialize time counter. - self.gravity_mag = 9.81 # default value of acceleration due to gravity + self._time = 0 # initialize time counter. + self.gravity_mag = 9.81 # default value of acceleration due to gravity + + self.observation_space = spaces.Box(-np.inf, np.inf, (18,), np.float32) + self.action_space = spaces.Box(-3.0, 3.0, (8,), np.float32) utils.EzPickle.__init__(self) - MujocoEnv.__init__(self, xml_path, frame_skip) + MujocoEnv.__init__(self, xml_path, frame_skip, self.observation_space) self.gravity_mag = float(abs(self.model.opt.gravity[2])) @@ -213,7 +216,11 @@ def env_bounding_box_norm(self): ------- env_bounding_box_sphere_radius: float """ - return self.norm(np.array([self.env_bounding_box, self.env_bounding_box, self.env_bounding_box])) + return self.norm( + np.array( + [self.env_bounding_box, self.env_bounding_box, self.env_bounding_box] + ) + ) @property def error_tolerance_norm(self): @@ -224,7 +231,9 @@ def error_tolerance_norm(self): ------- error_tolerance_norm_sphere_radius: float """ - return self.norm(np.array([self.error_tolerance, self.error_tolerance, self.error_tolerance])) + return self.norm( + np.array([self.error_tolerance, self.error_tolerance, self.error_tolerance]) + ) def step(self, a): """ @@ -240,7 +249,11 @@ def step(self, a): ob = self._get_obs() notdone = np.isfinite(ob).all() done = not notdone - info = {"reward_info": reward, "mujoco_qpos": self.mujoco_qpos, "mujoco_qvel": self.mujoco_qvel} + info = { + "reward_info": reward, + "mujoco_qpos": self.mujoco_qpos, + "mujoco_qvel": self.mujoco_qvel, + } return ob, reward, done, info def clip_action(self, action, a_min=-1.0, a_max=1.0): @@ -251,8 +264,7 @@ def clip_action(self, action, a_min=-1.0, a_max=1.0): return action def viewer_setup(self): - """This method is called when the viewer is initialized. Optionally implement this method, if you need to tinker with camera position and so forth. - """ + """This method is called when the viewer is initialized. Optionally implement this method, if you need to tinker with camera position and so forth.""" v = self.viewer v.cam.trackbodyid = 0 v.cam.distance = self.model.stat.extent * 2.5 @@ -344,12 +356,12 @@ def orientation_error(self, quat): Magnitude of error in orientation. """ - error = 0. + error = 0.0 rpy = multirotor_utils.quat2euler(quat) if self.reduce_heading_error: error += self.norm(rpy) else: - error += self.norm(rpy[:2]) # exclude error in yaw + error += self.norm(rpy[:2]) # exclude error in yaw return error @@ -457,8 +469,8 @@ def reward_velocity_towards_goal(self, error_xyz, velocity): """ if self.goal_reached(error_xyz): return self.max_reward_for_velocity_towards_goal - unit_xyz = error_xyz/(self.norm(error_xyz) + 1e-6) - velocity_direction = velocity/(self.norm(velocity) + 1e-6) + unit_xyz = error_xyz / (self.norm(error_xyz) + 1e-6) + velocity_direction = velocity / (self.norm(velocity) + 1e-6) reward = np.dot(unit_xyz, velocity_direction) return reward @@ -476,7 +488,11 @@ def is_done(self, ob): terminate: bool ``True`` if current episode is over else ``False``. """ - notdone = np.isfinite(ob).all() and self.is_within_env_bounds(ob[:3]) and (self._time < self.max_time_steps) + notdone = ( + np.isfinite(ob).all() + and self.is_within_env_bounds(ob[:3]) + and (self._time < self.max_time_steps) + ) done = not notdone return done @@ -517,7 +533,7 @@ def get_body_state_in_body_frame(self, body_name, xyz_ref=None): xyz, mat, vel (in body frame of reference), avel """ - xyz, mat, vel, avel = self.get_body_state(body_name) # in world frame + xyz, mat, vel, avel = self.get_body_state(body_name) # in world frame if xyz_ref is not None: xyz = np.array(xyz) - np.array(xyz_ref) diff --git a/gym_multirotor/envs/mujoco/quadrotor_plus_hover.py b/drone/gym_multirotor/envs/mujoco/quadrotor_plus_hover.py similarity index 68% rename from gym_multirotor/envs/mujoco/quadrotor_plus_hover.py rename to drone/gym_multirotor/envs/mujoco/quadrotor_plus_hover.py index 191dd55..ea31aff 100644 --- a/gym_multirotor/envs/mujoco/quadrotor_plus_hover.py +++ b/drone/gym_multirotor/envs/mujoco/quadrotor_plus_hover.py @@ -1,7 +1,7 @@ import numpy as np from gym_multirotor import utils from gym_multirotor.envs.mujoco.base_env import UAVBaseEnv -from gym.envs.registration import EnvSpec +from gymnasium.envs.registration import EnvSpec class QuadrotorPlusHoverEnv(UAVBaseEnv): @@ -14,14 +14,25 @@ class QuadrotorPlusHoverEnv(UAVBaseEnv): Args: frame_skip (int): Number of frames to skip before application of next action command to the environment from the control policy. """ - spec = EnvSpec(id='QuadrotorPlusHoverEnv-v0', - entry_point='gym_multirotor.envs.mujuco.quadrotor:QuadrotorPlusHoverEnv') - - def __init__(self, xml_name="quadrotor_plus.xml", frame_skip=5, env_bounding_box=1.2, randomize_reset=False): - super().__init__(xml_name=xml_name, - frame_skip=frame_skip, - env_bounding_box=env_bounding_box, randomize_reset=randomize_reset) + spec = EnvSpec( + id="QuadrotorPlusHoverEnv-v0", + entry_point="gym_multirotor.envs.mujuco.quadrotor:QuadrotorPlusHoverEnv", + ) + + def __init__( + self, + xml_name="quadrotor_plus.xml", + frame_skip=5, + env_bounding_box=1.2, + randomize_reset=False, + ): + super().__init__( + xml_name=xml_name, + frame_skip=frame_skip, + env_bounding_box=env_bounding_box, + randomize_reset=randomize_reset, + ) @property def hover_force(self): @@ -44,7 +55,9 @@ def get_motor_input(self, action): numpy.ndarray: Vector of motor inputs of shape (4,). """ motor_range = self.action_space.high.copy() - self.action_space.low.copy() - motor_inputs = self.hover_force + action * motor_range / (self.policy_range[1] - self.policy_range[0]) + motor_inputs = self.hover_force + action * motor_range / ( + self.policy_range[1] - self.policy_range[0] + ) return motor_inputs def step(self, action): @@ -63,7 +76,9 @@ def step(self, action): """ self._time += 1 - a = self.clip_action(action, a_min=self.policy_range[0], a_max=self.policy_range[1]) + a = self.clip_action( + action, a_min=self.policy_range[0], a_max=self.policy_range[1] + ) action_mujoco = self.get_motor_input(a) xyz_position_before = self.get_body_com("core")[:3].copy() self.do_simulation(action_mujoco, self.frame_skip) @@ -79,15 +94,22 @@ def step(self, action): reward, reward_info = self.get_reward(ob, a) - info = {"reward_info": reward_info, - "desired_goal": self.desired_position.copy(), - "mujoco_qpos": self.mujoco_qpos, - "mujoco_qvel": self.mujoco_qvel} + info = { + "reward_info": reward_info, + "desired_goal": self.desired_position.copy(), + "mujoco_qpos": self.mujoco_qpos, + "mujoco_qvel": self.mujoco_qvel, + } - done = self.is_done(ob) + terminated = self.is_done(ob) + truncated = False if self.observation_noise_std: - ob += np.random.uniform(low=-self.observation_noise_std, high=self.observation_noise_std, size=ob.shape) - return ob, reward, done, info + ob += np.random.uniform( + low=-self.observation_noise_std, + high=self.observation_noise_std, + size=ob.shape, + ) + return ob, reward, terminated, truncated, info def _get_obs(self): """ @@ -104,19 +126,21 @@ def _get_obs(self): self.mujoco_qpos = np.array(qpos) self.mujoco_qvel = np.array(qvel) - e_pos = qpos[0:3] - self.desired_position # position error + e_pos = qpos[0:3] - self.desired_position # position error if self.current_quat is not None: - self.previous_quat = self.current_quat.copy() # rotation matrix + self.previous_quat = self.current_quat.copy() # rotation matrix quat = np.array(qpos[3:7]) self.current_quat = np.array(quat) - rot_mat = utils.quat2rot(quat) # rotation matrix + rot_mat = utils.quat2rot(quat) # rotation matrix vel = np.array(self.data.qvel[:3]) # angular_vel = np.array(self.sim.data.get_body_xvelr("core")) - angular_vel = np.array(self.data.qvel[3:6]) # angular velocity of core of the robot in body frame. + angular_vel = np.array( + self.data.qvel[3:6] + ) # angular velocity of core of the robot in body frame. return np.concatenate([e_pos, rot_mat.flatten(), vel, angular_vel]).flatten() @@ -138,23 +162,45 @@ def get_reward(self, ob, a): reward_position = self.norm(ob[0:3]) * (-self.position_reward_constant) - reward_orientation = self.orientation_error(self.data.qpos[3:7]) * (-self.orientation_reward_constant) + reward_orientation = self.orientation_error(self.data.qpos[3:7]) * ( + -self.orientation_reward_constant + ) - reward_linear_velocity = self.norm(ob[12:15]) * (-self.linear_velocity_reward_constant) + reward_linear_velocity = self.norm(ob[12:15]) * ( + -self.linear_velocity_reward_constant + ) - reward_angular_velocity = self.norm(ob[15:18]) * (-self.angular_velocity_reward_constant) + reward_angular_velocity = self.norm(ob[15:18]) * ( + -self.angular_velocity_reward_constant + ) reward_action = self.norm(a) * (-self.action_reward_constant) - extra_bonus = self.bonus_reward_to_achieve_goal(ob[:3]) # EXTRA BONUS TO ACHIEVE THE GOAL + extra_bonus = self.bonus_reward_to_achieve_goal( + ob[:3] + ) # EXTRA BONUS TO ACHIEVE THE GOAL - extra_penalty = - self.bound_violation_penalty(ob[:3]) # PENALTY for bound violation + extra_penalty = -self.bound_violation_penalty( + ob[:3] + ) # PENALTY for bound violation reward_velocity_towards_goal = 0.0 if self.norm(ob[0:3]) > self.error_tolerance_norm: - reward_velocity_towards_goal += self.reward_velocity_towards_goal(error_xyz=ob[:3], velocity=ob[12:15]) - - rewards = (reward_position, reward_orientation, reward_linear_velocity, reward_angular_velocity, reward_action, alive_bonus, extra_bonus, extra_penalty, reward_velocity_towards_goal) + reward_velocity_towards_goal += self.reward_velocity_towards_goal( + error_xyz=ob[:3], velocity=ob[12:15] + ) + + rewards = ( + reward_position, + reward_orientation, + reward_linear_velocity, + reward_angular_velocity, + reward_action, + alive_bonus, + extra_bonus, + extra_penalty, + reward_velocity_towards_goal, + ) reward = sum(rewards) * self.reward_scaling_coefficient reward_info = dict( @@ -167,7 +213,7 @@ def get_reward(self, ob, a): extra_bonus=extra_bonus, extra_penalty=extra_penalty, velocity_towards_goal=reward_velocity_towards_goal, - all=rewards + all=rewards, ) return reward, reward_info @@ -186,22 +232,38 @@ def initialize_robot(self, randomize=True): """ if not randomize: - qpos_init = np.array([self.desired_position[0], self.desired_position[1], self.desired_position[2], 1., 0., 0., 0.]) + qpos_init = np.array( + [ + self.desired_position[0], + self.desired_position[1], + self.desired_position[2], + 1.0, + 0.0, + 0.0, + 0.0, + ] + ) qvel_init = np.zeros((6,)) return qpos_init, qvel_init # attitude (roll pitch yaw) - quat_init = np.array([1., 0., 0., 0.]) + quat_init = np.array([1.0, 0.0, 0.0, 0.0]) if self.disorient and self.sample_SO3: rot_mat = utils.sampleSO3() quat_init = utils.rot2quat(rot_mat) elif self.disorient: - attitude_euler_rand = np.random.uniform(low=-self.init_max_attitude, high=self.init_max_attitude, size=(3,)) + attitude_euler_rand = np.random.uniform( + low=-self.init_max_attitude, high=self.init_max_attitude, size=(3,) + ) quat_init = utils.euler2quat(attitude_euler_rand) # position (x, y, z) c = 0.2 - ep = np.random.uniform(low=-(self.env_bounding_box-c), high=(self.env_bounding_box-c), size=(3,)) + ep = np.random.uniform( + low=-(self.env_bounding_box - c), + high=(self.env_bounding_box - c), + size=(3,), + ) pos_init = ep + self.desired_position # velocity (vx, vy, vz) diff --git a/gym_multirotor/envs/mujoco/quadrotor_x_hover.py b/drone/gym_multirotor/envs/mujoco/quadrotor_x_hover.py similarity index 100% rename from gym_multirotor/envs/mujoco/quadrotor_x_hover.py rename to drone/gym_multirotor/envs/mujoco/quadrotor_x_hover.py diff --git a/gym_multirotor/envs/mujoco/tiltrotor_plus_hover.py b/drone/gym_multirotor/envs/mujoco/tiltrotor_plus_hover.py similarity index 71% rename from gym_multirotor/envs/mujoco/tiltrotor_plus_hover.py rename to drone/gym_multirotor/envs/mujoco/tiltrotor_plus_hover.py index 1e61abf..4acb0aa 100644 --- a/gym_multirotor/envs/mujoco/tiltrotor_plus_hover.py +++ b/drone/gym_multirotor/envs/mujoco/tiltrotor_plus_hover.py @@ -18,12 +18,13 @@ class TiltrotorPlus8DofHoverEnv(QuadrotorPlusHoverEnv): action_index_tilt = np.arange(4, 8) def __init__(self, xml_name="tiltrotor_plus_hover.xml", frame_skip=5): - self.tilt_position_reward_constant = 1.0 """float: Reward constant for position of the tilt servo. """ - super(TiltrotorPlus8DofHoverEnv, self).__init__(xml_name=xml_name, frame_skip=frame_skip) + super(TiltrotorPlus8DofHoverEnv, self).__init__( + xml_name=xml_name, frame_skip=frame_skip + ) def _get_obs(self): """ @@ -43,8 +44,8 @@ def _get_obs(self): rot_mat = utils.quat2rot(qpos[3:7]) tilt = qpos[7:11] - lvel = qvel[0:3] # linear velocity - avel = qvel[3:6] # angular velocity + lvel = qvel[0:3] # linear velocity + avel = qvel[3:6] # angular velocity obs = np.concatenate([e_pos, rot_mat.flatten(), lvel, avel, tilt]).ravel() return obs @@ -60,15 +61,21 @@ def get_motor_input(self, a): """ action_range = self.action_space.high - self.action_space.low - avg_actuation = np.array([self.mass * 9.81 * 0.25, - self.mass * 9.81 * 0.25, - self.mass * 9.81 * 0.25, - self.mass * 9.81 * 0.25, - 0.0, - 0.0, - 0.0, - 0.0]) # 4 propellers and 4 tilt-servos - motor_inputs = avg_actuation + a * action_range / (self.policy_range[1]-self.policy_range[0]) + avg_actuation = np.array( + [ + self.mass * 9.81 * 0.25, + self.mass * 9.81 * 0.25, + self.mass * 9.81 * 0.25, + self.mass * 9.81 * 0.25, + 0.0, + 0.0, + 0.0, + 0.0, + ] + ) # 4 propellers and 4 tilt-servos + motor_inputs = avg_actuation + a * action_range / ( + self.policy_range[1] - self.policy_range[0] + ) return motor_inputs def get_reward(self, ob, a): @@ -86,13 +93,15 @@ def get_reward(self, ob, a): """ ob_quad, ob_tilt = ob[:18].copy(), ob[18:22] action_quad, action_tilt = a[0:4], a[4:8] - reward_quad, reward_info = super(TiltrotorPlus8DofHoverEnv, self).get_reward(ob_quad, action_quad) + reward_quad, reward_info = super(TiltrotorPlus8DofHoverEnv, self).get_reward( + ob_quad, action_quad + ) reward_tilt = self.norm(ob_tilt) * (-self.tilt_position_reward_constant) reward_action_tilt = self.norm(action_tilt) * (-self.action_reward_constant) - reward_info['reward_tilt'] = reward_tilt - reward_info['action_tilt'] = reward_action_tilt + reward_info["reward_tilt"] = reward_tilt + reward_info["action_tilt"] = reward_action_tilt rewards = (reward_quad, reward_tilt, reward_action_tilt) reward = sum(rewards) * self.reward_scaling_coefficient @@ -111,23 +120,45 @@ def initialize_robot(self, randomize=True): - qvel_init (numpy.ndarray): Robot's initial velocity in mujoco with shape (10,). """ if not randomize: - qpos_init = np.array([self.desired_position[0], self.desired_position[1], self.desired_position[2], 1., 0., 0., 0., 0., 0., 0., 0]) + qpos_init = np.array( + [ + self.desired_position[0], + self.desired_position[1], + self.desired_position[2], + 1.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0, + ] + ) qvel_init = np.zeros((10,)) return qpos_init, qvel_init # attitude (roll pitch yaw) - quat_init = np.array([1., 0., 0., 0.]) + quat_init = np.array([1.0, 0.0, 0.0, 0.0]) if self.disorient and self.sample_SO3: rot_mat = utils.sampleSO3() quat_init = utils.rot2quat(rot_mat) elif self.disorient: - attitude_euler_rand = np.random.uniform(low=-self.init_max_attitude, high=self.init_max_attitude, size=(3,)) + attitude_euler_rand = np.random.uniform( + low=-self.init_max_attitude, high=self.init_max_attitude, size=(3,) + ) quat_init = utils.euler2quat(attitude_euler_rand) c = 0.2 - ep = np.random.uniform(low=-(self.env_bounding_box-c), high=(self.env_bounding_box-c), size=(3,)) + ep = np.random.uniform( + low=-(self.env_bounding_box - c), + high=(self.env_bounding_box - c), + size=(3,), + ) pos_init = ep + self.desired_position - tilt_init = np.random.uniform(low=-self.init_max_attitude, high=self.init_max_attitude, size=(4,)) + tilt_init = np.random.uniform( + low=-self.init_max_attitude, high=self.init_max_attitude, size=(4,) + ) vel_init = utils.sample_unit3d() * self.init_max_vel angular_vel_init = utils.sample_unit3d() * self.init_max_angular_vel tilt_vel = np.zeros((4,)) diff --git a/drone/gym_multirotor/utils/__init__.py b/drone/gym_multirotor/utils/__init__.py new file mode 100644 index 0000000..ebead89 --- /dev/null +++ b/drone/gym_multirotor/utils/__init__.py @@ -0,0 +1,14 @@ +from .rotation_transformations import quat2rot # noqa: F401 +from .rotation_transformations import rot2quat # noqa: F401 +from .rotation_transformations import quat2euler # noqa: F401 +from .rotation_transformations import euler2quat # noqa: F401 + +from .rand_sampling import sampleSO3 # noqa: F401 +from .rand_sampling import sample_unit3d # noqa: F401 +from .rand_sampling import sample_quat # noqa: F401 + +from .observation_utils import get_partial_ob_tiltrotor # noqa: F401 +from .observation_utils import get_ob_tiltrotor # noqa: F401 +from .observation_utils import get_ob_quadrotor # noqa: F401 + +from .misc import get_magnitude # noqa: F401 diff --git a/gym_multirotor/utils/low_pass_filter.py b/drone/gym_multirotor/utils/low_pass_filter.py similarity index 100% rename from gym_multirotor/utils/low_pass_filter.py rename to drone/gym_multirotor/utils/low_pass_filter.py diff --git a/gym_multirotor/utils/misc.py b/drone/gym_multirotor/utils/misc.py similarity index 100% rename from gym_multirotor/utils/misc.py rename to drone/gym_multirotor/utils/misc.py diff --git a/gym_multirotor/utils/noise.py b/drone/gym_multirotor/utils/noise.py similarity index 100% rename from gym_multirotor/utils/noise.py rename to drone/gym_multirotor/utils/noise.py diff --git a/gym_multirotor/utils/observation_utils.py b/drone/gym_multirotor/utils/observation_utils.py similarity index 96% rename from gym_multirotor/utils/observation_utils.py rename to drone/gym_multirotor/utils/observation_utils.py index 96cb3c7..fe68035 100644 --- a/gym_multirotor/utils/observation_utils.py +++ b/drone/gym_multirotor/utils/observation_utils.py @@ -31,7 +31,7 @@ def get_ob_quadrotor(mujoco_pos, mujoco_vel): :return: numpy observation vector [shape (18,)] """ - pos = mujoco_pos[:3] # possibly this pos represents error + pos = mujoco_pos[:3] # possibly this pos represents error quat = mujoco_pos[3:7] rot_mat = quat2rot(quat) diff --git a/gym_multirotor/utils/plotters.py b/drone/gym_multirotor/utils/plotters.py similarity index 63% rename from gym_multirotor/utils/plotters.py rename to drone/gym_multirotor/utils/plotters.py index 481c5cb..585e5cd 100644 --- a/gym_multirotor/utils/plotters.py +++ b/drone/gym_multirotor/utils/plotters.py @@ -3,15 +3,16 @@ from gym_multirotor.utils.rotation_transformations import quat2euler -def plot_xyz(time, - state, - super_title='X-Y-Z plots', - ylabels=('$x$', '$y$', '$z$'), - xlabel='time', - save_as='XYZ.pdf', - lineWidth=0.5 - ): - fig, axs = plt.subplots(3, sharex='all') +def plot_xyz( + time, + state, + super_title="X-Y-Z plots", + ylabels=("$x$", "$y$", "$z$"), + xlabel="time", + save_as="XYZ.pdf", + lineWidth=0.5, +): + fig, axs = plt.subplots(3, sharex="all") for i in range(3): axs[i].plot(time, state[:, i], lineWidth=lineWidth) @@ -32,7 +33,9 @@ def plot_xyz(time, plt.savefig(save_as, dpi=150) -def plot_rpy(time, state, super_title="Roll-Pitch-Yaw", save_as='roll_pitch_yaw.pdf', lineWidth=2): +def plot_rpy( + time, state, super_title="Roll-Pitch-Yaw", save_as="roll_pitch_yaw.pdf", lineWidth=2 +): quats = state[:, 3:7] euler = [] @@ -40,13 +43,13 @@ def plot_rpy(time, state, super_title="Roll-Pitch-Yaw", save_as='roll_pitch_yaw. euler.append(quat2euler(q)) euler = np.array(euler) - fig, axs = plt.subplots(3, sharex='all') + fig, axs = plt.subplots(3, sharex="all") - ylabels = ['$\phi (^{\circ})$', '$\\theta (^{\circ})$', '$\psi (^{\circ})$'] + ylabels = ["$\phi (^{\circ})$", "$\\theta (^{\circ})$", "$\psi (^{\circ})$"] for i in range(3): axs[i].plot(time, euler[:, i] * 180 / np.pi, lineWidth=lineWidth) axs[i].grid(True) - axs[i].set(xlabel='time', ylabel=ylabels[i]) + axs[i].set(xlabel="time", ylabel=ylabels[i]) # axs[i].set_yticks(np.arange(-15, 15)) # axs[i].minorticks_on() @@ -65,18 +68,31 @@ def plot_rpy(time, state, super_title="Roll-Pitch-Yaw", save_as='roll_pitch_yaw. plt.savefig(save_as, dpi=150) -def plot_action_tiltrotor(time, action, set_super_title=True, save_as=('thrust.pdf', 'tilt.pdf'), lineWidth=0.5, - super_title=('Config1-Thrust', 'Config1-Tilt')): - fig, axs = plt.subplots(4, sharex='all') - - ylabels = ['$rotor_{front}$', '$rotor_{left}$', '$rotor_{back}$', '$rotor_{right}$', - '$\\theta^{tilt}_{front} (^{\circ})$', '$\\theta^{tilt}_{left} (^{\circ})$', - '$\\theta^{tilt}_{back} (^{\circ})$', '$\\theta^{tilt}_{right} (^{\circ})$'] +def plot_action_tiltrotor( + time, + action, + set_super_title=True, + save_as=("thrust.pdf", "tilt.pdf"), + lineWidth=0.5, + super_title=("Config1-Thrust", "Config1-Tilt"), +): + fig, axs = plt.subplots(4, sharex="all") + + ylabels = [ + "$rotor_{front}$", + "$rotor_{left}$", + "$rotor_{back}$", + "$rotor_{right}$", + "$\\theta^{tilt}_{front} (^{\circ})$", + "$\\theta^{tilt}_{left} (^{\circ})$", + "$\\theta^{tilt}_{back} (^{\circ})$", + "$\\theta^{tilt}_{right} (^{\circ})$", + ] for i in range(4): axs[i].plot(time, action[:, i], lineWidth=lineWidth) axs[i].grid(True) - axs[i].set(xlabel='time', ylabel=ylabels[i]) + axs[i].set(xlabel="time", ylabel=ylabels[i]) axs[i].set_ylim(0, 1.2) # axs[i].set_xticks(time[::200]) axs[i].set_xlim(time[0], time[-1]) @@ -94,11 +110,11 @@ def plot_action_tiltrotor(time, action, set_super_title=True, save_as=('thrust.p if save_as is not None: plt.savefig(save_as[0], dpi=150) - fig, axs = plt.subplots(4, sharex='all') + fig, axs = plt.subplots(4, sharex="all") for i in range(4): - axs[i].plot(time, action[:, i + 4] * 1.04 * 180. / np.pi, lineWidth=lineWidth) + axs[i].plot(time, action[:, i + 4] * 1.04 * 180.0 / np.pi, lineWidth=lineWidth) axs[i].grid(True) - axs[i].set(xlabel='time', ylabel=ylabels[i + 4]) + axs[i].set(xlabel="time", ylabel=ylabels[i + 4]) axs[i].set_ylim(-61, 62) axs[i].set_xlim(time[0], time[-1]) # axs[i].set_xticks(time[::200]) @@ -115,4 +131,3 @@ def plot_action_tiltrotor(time, action, set_super_title=True, save_as=('thrust.p if save_as is not None: plt.savefig(save_as[1], dpi=150) - diff --git a/gym_multirotor/utils/rand_sampling.py b/drone/gym_multirotor/utils/rand_sampling.py similarity index 94% rename from gym_multirotor/utils/rand_sampling.py rename to drone/gym_multirotor/utils/rand_sampling.py index 4138500..00543c8 100644 --- a/gym_multirotor/utils/rand_sampling.py +++ b/drone/gym_multirotor/utils/rand_sampling.py @@ -13,7 +13,7 @@ def sampleSO3(): :return: rotation matrix sampled from uniform distribution as numpy array of shape (3,3). """ - rand_rot = special_ortho_group.rvs(3) # uniform sample from SO(3) + rand_rot = special_ortho_group.rvs(3) # uniform sample from SO(3) return rand_rot @@ -27,7 +27,7 @@ def sample_unit3d(): :return: numpy 3D unit vector sampled from uniform distribution """ - phi = np.random.uniform(0, 2*np.pi) + phi = np.random.uniform(0, 2 * np.pi) costheta = np.random.uniform(-1, 1) theta = np.arccos(costheta) x = np.sin(theta) * np.cos(phi) @@ -35,6 +35,7 @@ def sample_unit3d(): z = np.cos(theta) return np.array([x, y, z]) + # TODO: Fix the random distribution of unit vector # def sample_unit3d(np_random): # """ @@ -84,7 +85,6 @@ def sample_unit3d(): # return quat - def sample_quat(): """ This function samples quaternion from uniform random distribution @@ -147,11 +147,11 @@ def quaternion(self): def rpy(self, degrees=False): rmat = self.rotmat() - euler = Rotation.from_matrix(rmat).as_euler(seq='xyz', degrees=degrees) + euler = Rotation.from_matrix(rmat).as_euler(seq="xyz", degrees=degrees) return euler -if __name__ == '__main__': +if __name__ == "__main__": random_state = np.random.RandomState(seed=10) ur = UniformRotation(random_state=random_state) a1 = [] @@ -167,6 +167,6 @@ def rpy(self, degrees=False): a2 = np.array(a2) np.testing.assert_array_almost_equal(a1, a2) - print('Test Successfull...') + print("Test Successfull...") print(random_state.standard_normal(size=4)) diff --git a/gym_multirotor/utils/robot_logger.py b/drone/gym_multirotor/utils/robot_logger.py similarity index 100% rename from gym_multirotor/utils/robot_logger.py rename to drone/gym_multirotor/utils/robot_logger.py diff --git a/gym_multirotor/utils/rotation_transformations.py b/drone/gym_multirotor/utils/rotation_transformations.py similarity index 100% rename from gym_multirotor/utils/rotation_transformations.py rename to drone/gym_multirotor/utils/rotation_transformations.py diff --git a/gym_multirotor/utils/thurst_motor.py b/drone/gym_multirotor/utils/thurst_motor.py similarity index 88% rename from gym_multirotor/utils/thurst_motor.py rename to drone/gym_multirotor/utils/thurst_motor.py index aa71882..55a0295 100644 --- a/gym_multirotor/utils/thurst_motor.py +++ b/drone/gym_multirotor/utils/thurst_motor.py @@ -49,8 +49,19 @@ class ThrustMotor: """ def __init__( - self, kf, km, control_timestep, n_motor, random_state, time_constant=None, - mu=0.0, theta=0.15, sigma=0.15, sigma_min=0.05, sigma_decay=1, add_noise=False + self, + kf, + km, + control_timestep, + n_motor, + random_state, + time_constant=None, + mu=0.0, + theta=0.15, + sigma=0.15, + sigma_min=0.05, + sigma_decay=1, + add_noise=False, ): self.kf = kf self.km = km @@ -58,8 +69,13 @@ def __init__( self.add_noise = add_noise self.motor_noise = OUNoise( - size=n_motor, random_state=random_state, - mu=mu, theta=theta, sigma=sigma, sigma_decay=sigma_decay, sigma_min=sigma_min + size=n_motor, + random_state=random_state, + mu=mu, + theta=theta, + sigma=sigma, + sigma_decay=sigma_decay, + sigma_min=sigma_min, ) self.lpf_motor_speed = FirstOrderLowPassFilter( @@ -127,7 +143,7 @@ def speed_command2actual(self, speed_command): if self.add_noise: speed_actual += self.motor_noise.sample() - speed_actual = np.clip(speed_actual, a_min=0., a_max=np.inf) + speed_actual = np.clip(speed_actual, a_min=0.0, a_max=np.inf) return speed_actual def thrust_command2actual(self, thrust_command): @@ -165,8 +181,8 @@ def reset(self): self.lpf_motor_speed.reset() -if __name__ == '__main__': - RPM_2_RAD_PER_SEC = 2 * np.pi / 60. +if __name__ == "__main__": + RPM_2_RAD_PER_SEC = 2 * np.pi / 60.0 kf = 6.11 * 10**-8 / (RPM_2_RAD_PER_SEC**2) km = 1.5 * 10**-9 / (RPM_2_RAD_PER_SEC**2) @@ -185,7 +201,7 @@ def reset(self): sigma=0.15, sigma_min=0.05, sigma_decay=1, - add_noise=True + add_noise=True, ) for i in range(100): diff --git a/main.py b/drone/main.py similarity index 98% rename from main.py rename to drone/main.py index 530b724..6ec7058 100644 --- a/main.py +++ b/drone/main.py @@ -1,5 +1,4 @@ from gym_multirotor.envs.mujoco.quadrotor_plus_hover import QuadrotorPlusHoverEnv -import gym import os from stable_baselines3 import PPO diff --git a/gym_multirotor/__init__.py b/gym_multirotor/__init__.py deleted file mode 100644 index 4d55000..0000000 --- a/gym_multirotor/__init__.py +++ /dev/null @@ -1,25 +0,0 @@ -from gym.envs.registration import register -from gym_multirotor import envs -from gym_multirotor.envs import mujoco -from gym_multirotor.envs.mujoco import * - - -# Quadrotors with Plus(+)-configuration -register( - id='QuadrotorPlusHoverEnv-v0', - entry_point='gym_multirotor.envs.mujoco.quadrotor_plus_hover:QuadrotorPlusHoverEnv' -) - - -register( - id='TiltrotorPlus8DofHoverEnv-v0', - entry_point='gym_multirotor.envs.mujoco.tiltrotor_plus_hover:TiltrotorPlus8DofHoverEnv' -) - -# Quadrotor with X-configuration -register( - id='QuadrotorXHoverEnv-v0', - entry_point='gym_multirotor.envs.mujoco.quadrotor_x_hover:QuadrotorXHoverEnv' -) - - diff --git a/gym_multirotor/__pycache__/__init__.cpython-310.pyc b/gym_multirotor/__pycache__/__init__.cpython-310.pyc deleted file mode 100644 index 9e94d23..0000000 Binary files a/gym_multirotor/__pycache__/__init__.cpython-310.pyc and /dev/null differ diff --git a/gym_multirotor/envs/__pycache__/__init__.cpython-310.pyc b/gym_multirotor/envs/__pycache__/__init__.cpython-310.pyc deleted file mode 100644 index c49b064..0000000 Binary files a/gym_multirotor/envs/__pycache__/__init__.cpython-310.pyc and /dev/null differ diff --git a/gym_multirotor/envs/mujoco/__init__.py b/gym_multirotor/envs/mujoco/__init__.py deleted file mode 100644 index f5477ab..0000000 --- a/gym_multirotor/envs/mujoco/__init__.py +++ /dev/null @@ -1 +0,0 @@ -from gym_multirotor.envs.mujoco.base_env import UAVBaseEnv diff --git a/gym_multirotor/envs/mujoco/__pycache__/__init__.cpython-310.pyc b/gym_multirotor/envs/mujoco/__pycache__/__init__.cpython-310.pyc deleted file mode 100644 index dc47846..0000000 Binary files a/gym_multirotor/envs/mujoco/__pycache__/__init__.cpython-310.pyc and /dev/null differ diff --git a/gym_multirotor/envs/mujoco/__pycache__/base_env.cpython-310.pyc b/gym_multirotor/envs/mujoco/__pycache__/base_env.cpython-310.pyc deleted file mode 100644 index 4ed277c..0000000 Binary files a/gym_multirotor/envs/mujoco/__pycache__/base_env.cpython-310.pyc and /dev/null differ diff --git a/gym_multirotor/envs/mujoco/__pycache__/quadrotor_plus_hover.cpython-310.pyc b/gym_multirotor/envs/mujoco/__pycache__/quadrotor_plus_hover.cpython-310.pyc deleted file mode 100644 index 53a25b3..0000000 Binary files a/gym_multirotor/envs/mujoco/__pycache__/quadrotor_plus_hover.cpython-310.pyc and /dev/null differ diff --git a/gym_multirotor/utils/__init__.py b/gym_multirotor/utils/__init__.py deleted file mode 100644 index 00c912c..0000000 --- a/gym_multirotor/utils/__init__.py +++ /dev/null @@ -1,14 +0,0 @@ -from .rotation_transformations import quat2rot -from .rotation_transformations import rot2quat -from .rotation_transformations import quat2euler -from .rotation_transformations import euler2quat - -from .rand_sampling import sampleSO3 -from .rand_sampling import sample_unit3d -from .rand_sampling import sample_quat - -from .observation_utils import get_partial_ob_tiltrotor -from .observation_utils import get_ob_tiltrotor -from .observation_utils import get_ob_quadrotor - -from .misc import get_magnitude diff --git a/gym_multirotor/utils/__pycache__/__init__.cpython-310.pyc b/gym_multirotor/utils/__pycache__/__init__.cpython-310.pyc deleted file mode 100644 index ecb461e..0000000 Binary files a/gym_multirotor/utils/__pycache__/__init__.cpython-310.pyc and /dev/null differ diff --git a/gym_multirotor/utils/__pycache__/misc.cpython-310.pyc b/gym_multirotor/utils/__pycache__/misc.cpython-310.pyc deleted file mode 100644 index 325da87..0000000 Binary files a/gym_multirotor/utils/__pycache__/misc.cpython-310.pyc and /dev/null differ diff --git a/gym_multirotor/utils/__pycache__/observation_utils.cpython-310.pyc b/gym_multirotor/utils/__pycache__/observation_utils.cpython-310.pyc deleted file mode 100644 index 7b8d51a..0000000 Binary files a/gym_multirotor/utils/__pycache__/observation_utils.cpython-310.pyc and /dev/null differ diff --git a/gym_multirotor/utils/__pycache__/rand_sampling.cpython-310.pyc b/gym_multirotor/utils/__pycache__/rand_sampling.cpython-310.pyc deleted file mode 100644 index 6405b12..0000000 Binary files a/gym_multirotor/utils/__pycache__/rand_sampling.cpython-310.pyc and /dev/null differ diff --git a/gym_multirotor/utils/__pycache__/rotation_transformations.cpython-310.pyc b/gym_multirotor/utils/__pycache__/rotation_transformations.cpython-310.pyc deleted file mode 100644 index 953618e..0000000 Binary files a/gym_multirotor/utils/__pycache__/rotation_transformations.cpython-310.pyc and /dev/null differ diff --git a/pyproject.toml b/pyproject.toml new file mode 100644 index 0000000..4898ebc --- /dev/null +++ b/pyproject.toml @@ -0,0 +1,37 @@ +[tool.poetry] +name = "drone" +version = "0.1.0" +description = "" +authors = ["Your Name "] +readme = "README.md" + +[tool.poetry.dependencies] +python = "^3.12" +numpy = "1.26.4" +scipy = "^1.14.1" +matplotlib = "^3.10.0" +mujoco = "^3.2.6" +pyyaml = "^6.0.2" +stable-baselines3 = "^2.4.0" +shimmy = "^2.0.0" +gymnasium = "^1.0.0" +pandas = "^2.2.3" +imageio = "^2.36.1" + +[[tool.poetry.source]] +name = "rocm-pytorch" +url = "https://download.pytorch.org/whl/nightly/rocm6.2" +priority = "explicit" + +[tool.poetry.group.rocm] +optional = true + +[tool.poetry.group.rocm.dependencies] +pytorch-triton-rocm = { version = "3.1.0", source = "rocm-pytorch" } +torch = {version = "^2.6.0.dev20241122+rocm6.2", source = "rocm-pytorch"} +torchvision = {version = "^0.20.0.dev20241206+rocm6.2", source = "rocm-pytorch"} +torchaudio = {version = "^2.5.0.dev20241206+rocm6.2", source = "rocm-pytorch"} + +[build-system] +requires = ["poetry-core"] +build-backend = "poetry.core.masonry.api" diff --git a/requirements.txt b/requirements.txt deleted file mode 100644 index 95a206d..0000000 --- a/requirements.txt +++ /dev/null @@ -1,7 +0,0 @@ -numpy -gym -scipy -matplotlib -baselines -PyYAML -mujoco \ No newline at end of file