Skip to content

Commit

Permalink
Further clean up (removing DYN, TUN action spaces)
Browse files Browse the repository at this point in the history
  • Loading branch information
JacopoPan committed Apr 16, 2023
1 parent 0ff20a6 commit f7846ed
Show file tree
Hide file tree
Showing 13 changed files with 86 additions and 796 deletions.
26 changes: 0 additions & 26 deletions gym_pybullet_drones/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,11 +5,6 @@
entry_point='gym_pybullet_drones.envs:CtrlAviary',
)

register(
id='dyn-aviary-v0',
entry_point='gym_pybullet_drones.envs:DynAviary',
)

register(
id='velocity-aviary-v0',
entry_point='gym_pybullet_drones.envs:VelocityAviary',
Expand All @@ -20,14 +15,6 @@
entry_point='gym_pybullet_drones.envs:VisionAviary',
)




register(
id='takeoff-aviary-v0',
entry_point='gym_pybullet_drones.envs.single_agent_rl:TakeoffAviary',
)

register(
id='hover-aviary-v0',
entry_point='gym_pybullet_drones.envs.single_agent_rl:HoverAviary',
Expand All @@ -38,14 +25,6 @@
entry_point='gym_pybullet_drones.envs.single_agent_rl:FlyThruGateAviary',
)

register(
id='tune-aviary-v0',
entry_point='gym_pybullet_drones.envs.single_agent_rl:TuneAviary',
)




register(
id='flock-aviary-v0',
entry_point='gym_pybullet_drones.envs.multi_agent_rl:FlockAviary',
Expand All @@ -55,8 +34,3 @@
id='leaderfollower-aviary-v0',
entry_point='gym_pybullet_drones.envs.multi_agent_rl:LeaderFollowerAviary',
)

register(
id='meetup-aviary-v0',
entry_point='gym_pybullet_drones.envs.multi_agent_rl:MeetupAviary',
)
12 changes: 0 additions & 12 deletions gym_pybullet_drones/envs/BaseAviary.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,6 @@ def __init__(self,
obstacles=False,
user_debug_gui=True,
vision_attributes=False,
dynamics_attributes=False,
output_folder='results'
):
"""Initialization of a generic aviary environment.
Expand Down Expand Up @@ -70,8 +69,6 @@ def __init__(self,
Whether to draw the drones' axes and the GUI RPMs sliders.
vision_attributes : bool, optional
Whether to allocate the attributes needed by vision-based aviary subclasses.
dynamics_attributes : bool, optional
Whether to allocate the attributes needed by subclasses accepting thrust and torques inputs.
"""
#### Constants #############################################
Expand Down Expand Up @@ -140,15 +137,6 @@ def __init__(self,
# TODO: This doesn't appear to work in general
self.ONBOARD_IMG_PATH = os.path.join(self.OUTPUT_FOLDER, "recording_" + datetime.now().strftime("%m.%d.%Y_%H.%M.%S"))
os.makedirs(os.path.dirname(self.ONBOARD_IMG_PATH), exist_ok=True)
#### Create attributes for dynamics control inputs #########
self.DYNAMICS_ATTR = dynamics_attributes
if self.DYNAMICS_ATTR:
if self.DRONE_MODEL == DroneModel.CF2X:
self.A = np.array([ [1, 1, 1, 1], [1/np.sqrt(2), 1/np.sqrt(2), -1/np.sqrt(2), -1/np.sqrt(2)], [-1/np.sqrt(2), 1/np.sqrt(2), 1/np.sqrt(2), -1/np.sqrt(2)], [-1, 1, -1, 1] ])
elif self.DRONE_MODEL in [DroneModel.CF2P, DroneModel.HB]:
self.A = np.array([ [1, 1, 1, 1], [0, 1, 0, -1], [-1, 0, 1, 0], [-1, 1, -1, 1] ])
self.INV_A = np.linalg.inv(self.A)
self.B_COEFF = np.array([1/self.KF, 1/(self.KF*self.L), 1/(self.KF*self.L), 1/self.KM])
#### Connect to PyBullet ###################################
if self.GUI:
#### With debug GUI ########################################
Expand Down
43 changes: 3 additions & 40 deletions gym_pybullet_drones/envs/multi_agent_rl/BaseMultiagentAviary.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,16 +2,14 @@
import numpy as np
import pybullet as p
from gymnasium import spaces
from ray.rllib.env.multi_agent_env import MultiAgentEnv

from gym_pybullet_drones.envs.BaseAviary import BaseAviary
from gym_pybullet_drones.utils.enums import DroneModel, Physics
from gym_pybullet_drones.envs.single_agent_rl.BaseSingleAgentAviary import ActionType, ObservationType
from gym_pybullet_drones.utils.utils import nnlsRPM
from gym_pybullet_drones.control.DSLPIDControl import DSLPIDControl
from gym_pybullet_drones.control.SimplePIDControl import SimplePIDControl

class BaseMultiagentAviary(BaseAviary, MultiAgentEnv):
class BaseMultiagentAviary(BaseAviary):
"""Base multi-agent environment class for reinforcement learning."""

################################################################################
Expand Down Expand Up @@ -68,11 +66,7 @@ def __init__(self,
if num_drones < 2:
print("[ERROR] in BaseMultiagentAviary.__init__(), num_drones should be >= 2")
exit()
if act == ActionType.TUN:
print("[ERROR] in BaseMultiagentAviary.__init__(), ActionType.TUN can only used with BaseSingleAgentAviary")
exit()
vision_attributes = True if obs == ObservationType.RGB else False
dynamics_attributes = True if act in [ActionType.DYN, ActionType.ONE_D_DYN] else False
self.OBS_TYPE = obs
self.ACT_TYPE = act
self.EPISODE_LEN_SEC = 5
Expand All @@ -81,8 +75,6 @@ def __init__(self,
os.environ['KMP_DUPLICATE_LIB_OK']='True'
if drone_model in [DroneModel.CF2X, DroneModel.CF2P]:
self.ctrl = [DSLPIDControl(drone_model=DroneModel.CF2X) for i in range(num_drones)]
elif drone_model == DroneModel.HB:
self.ctrl = [SimplePIDControl(drone_model=DroneModel.HB) for i in range(num_drones)]
else:
print("[ERROR] in BaseMultiagentAviary.__init()__, no controller is available for the specified drone_model")
super().__init__(drone_model=drone_model,
Expand All @@ -98,7 +90,6 @@ def __init__(self,
obstacles=True, # Add obstacles for RGB observations and/or FlyThruGate
user_debug_gui=False, # Remove of RPM sliders from all single agent learning aviaries
vision_attributes=vision_attributes,
dynamics_attributes=dynamics_attributes
)
#### Set a limit on the maximum target speed ###############
if act == ActionType.VEL:
Expand Down Expand Up @@ -149,11 +140,11 @@ def _actionSpace(self):
indexed by drone Id in integer format.
"""
if self.ACT_TYPE in [ActionType.RPM, ActionType.DYN, ActionType.VEL]:
if self.ACT_TYPE in [ActionType.RPM, ActionType.VEL]:
size = 4
elif self.ACT_TYPE==ActionType.PID:
size = 3
elif self.ACT_TYPE in [ActionType.ONE_D_RPM, ActionType.ONE_D_DYN, ActionType.ONE_D_PID]:
elif self.ACT_TYPE in [ActionType.ONE_D_RPM, ActionType.ONE_D_PID]:
size = 1
else:
print("[ERROR] in BaseMultiagentAviary._actionSpace()")
Expand Down Expand Up @@ -196,20 +187,6 @@ def _preprocessAction(self,
for k, v in action.items():
if self.ACT_TYPE == ActionType.RPM:
rpm[int(k),:] = np.array(self.HOVER_RPM * (1+0.05*v))
elif self.ACT_TYPE == ActionType.DYN:
rpm[int(k),:] = nnlsRPM(thrust=(self.GRAVITY*(v[0]+1)),
x_torque=(0.05*self.MAX_XY_TORQUE*v[1]),
y_torque=(0.05*self.MAX_XY_TORQUE*v[2]),
z_torque=(0.05*self.MAX_Z_TORQUE*v[3]),
counter=self.step_counter,
max_thrust=self.MAX_THRUST,
max_xy_torque=self.MAX_XY_TORQUE,
max_z_torque=self.MAX_Z_TORQUE,
a=self.A,
inv_a=self.INV_A,
b_coeff=self.B_COEFF,
gui=self.GUI
)
elif self.ACT_TYPE == ActionType.PID:
state = self._getDroneStateVector(int(k))
rpm_k, _, _ = self.ctrl[int(k)].computeControl(control_timestep=self.AGGR_PHY_STEPS*self.TIMESTEP,
Expand Down Expand Up @@ -238,20 +215,6 @@ def _preprocessAction(self,
rpm[int(k),:] = temp
elif self.ACT_TYPE == ActionType.ONE_D_RPM:
rpm[int(k),:] = np.repeat(self.HOVER_RPM * (1+0.05*v), 4)
elif self.ACT_TYPE == ActionType.ONE_D_DYN:
rpm[int(k),:] = nnlsRPM(thrust=(self.GRAVITY*(1+0.05*v[0])),
x_torque=0,
y_torque=0,
z_torque=0,
counter=self.step_counter,
max_thrust=self.MAX_THRUST,
max_xy_torque=self.MAX_XY_TORQUE,
max_z_torque=self.MAX_Z_TORQUE,
a=self.A,
inv_a=self.INV_A,
b_coeff=self.B_COEFF,
gui=self.GUI
)
elif self.ACT_TYPE == ActionType.ONE_D_PID:
state = self._getDroneStateVector(int(k))
rpm, _, _ = self.ctrl[k].computeControl(control_timestep=self.AGGR_PHY_STEPS*self.TIMESTEP,
Expand Down
208 changes: 0 additions & 208 deletions gym_pybullet_drones/envs/multi_agent_rl/MeetupAviary.py

This file was deleted.

Loading

0 comments on commit f7846ed

Please sign in to comment.