From 5899dda31cd54d5ef93ed2ab298676cf447d750d Mon Sep 17 00:00:00 2001 From: Jacopo Panerati Date: Wed, 19 Aug 2020 12:23:29 -0400 Subject: [PATCH] Renaming of single agent examples --- README.md | 38 +++++++++++-------- examples/{run_flight.py => sa_flight.py} | 0 examples/{run_learning.py => sa_learning.py} | 0 examples/{run_trace.py => sa_trace.py} | 0 .../control/SingleDroneControl.py | 5 --- gym_pybullet_drones/envs/MultiDroneEnv.py | 5 --- gym_pybullet_drones/envs/SingleDroneEnv.py | 5 --- 7 files changed, 22 insertions(+), 31 deletions(-) rename examples/{run_flight.py => sa_flight.py} (100%) rename examples/{run_learning.py => sa_learning.py} (100%) rename examples/{run_trace.py => sa_trace.py} (100%) diff --git a/README.md b/README.md index e9214df59..7af2e31b4 100644 --- a/README.md +++ b/README.md @@ -44,39 +44,39 @@ $ pip install -e . ## Use -There are 4 main scripts in `examples/`: `run_physics.py`, `run_trace.py`, `run_flight.py`, `test_physics.py` +There are 4 main scripts in `examples/`: `sa_trace.py`, `sa_flight.py`, `sa_learning.py`, `test_physics.py` - `test_physics.py` can be used to test the effects of PyBullet's forces and torques to different [URDF links](http://wiki.ros.org/urdf/XML/link) in `p.WORLD_FRAME` and `p.LINK_FRAME` ``` $ conda activate myenv # If using a conda environment $ cd gym-pybullet-drones/examples/ -$ python run_physics.py +$ python test_physics.py ``` > Tip: also check the examples in [pybullet-examples](https://github.com/JacopoPan/pybullet-examples) -- `run_trace.py` replays and compare to a trace saved in [`trace.pkl`](https://github.com/JacopoPan/gym-pybullet-drones/tree/master/files/traces) +- `sa_trace.py` replays and compare to a trace saved in [`trace.pkl`](https://github.com/JacopoPan/gym-pybullet-drones/tree/master/files/traces) ``` $ conda activate myenv # If using a conda environment $ cd gym-pybullet-drones/examples/ -$ python run_trace.py +$ python sa_trace.py ``` alt text alt text -- `run_flight.py` runs an independent flight **using PID control** implemented in class [`SingleDroneControl`](https://github.com/JacopoPan/gym-pybullet-drones/tree/master/gym_pybullet_drones/control/SingleDroneControl.py) +- `sa_flight.py` runs an independent flight **using PID control** implemented in class [`SingleDroneControl`](https://github.com/JacopoPan/gym-pybullet-drones/tree/master/gym_pybullet_drones/control/SingleDroneControl.py) ``` $ conda activate myenv # If using a conda environment $ cd gym-pybullet-drones/examples/ -$ python run_flight.py +$ python sa_flight.py ``` > Tip: use the GUI's sliders and button `Use GUI RPM` to override the control with interactive inputs alt text alt text -- `run_learning.py` is an **RL example** to learn take-off using `stable-baselines3`'s [A2C](https://stable-baselines3.readthedocs.io/en/master/modules/a2c.html) or `rllib`'s [PPO](https://docs.ray.io/en/master/rllib-algorithms.html#ppo) +- `sa_learning.py` is an **RL example** to learn take-off using `stable-baselines3`'s [A2C](https://stable-baselines3.readthedocs.io/en/master/modules/a2c.html) or `rllib`'s [PPO](https://docs.ray.io/en/master/rllib-algorithms.html#ppo) ``` $ conda activate myenv # If using a conda environment $ cd gym-pybullet-drones/examples/ -$ python run_learning.py +$ python sa_learning.py ``` alt text alt text alt text alt text @@ -85,7 +85,7 @@ $ python run_learning.py ## SingleDroneEnv -A single quadrotor enviroment can be created with `SingleDroneEnv()`—see [`run_flight.py`](https://github.com/JacopoPan/gym-pybullet-drones/blob/master/examples/run_flight.py) for an example +A single quadrotor enviroment can be created with `SingleDroneEnv()`—see [`sa_flight.py`](https://github.com/JacopoPan/gym-pybullet-drones/blob/master/examples/sa_flight.py) for an example ``` >>> env = SingleDroneEnv( \ >>> drone_model=DroneModel.CF2X, \ # See DroneModel.py for other quadcopter models (remove this comment) @@ -100,9 +100,9 @@ A single quadrotor enviroment can be created with `SingleDroneEnv()`—see [`run >>> record=False, \ # Whether to save a .mp4 video in gym-pybullet-drones/files/saves/ (remove this comment) >>> user="Default") # String to choose reward and done functions in class SingleDroneUserDefinedFunctions (remove this comment) ```` -Or using `gym.make()`—see [`run_learning.py`](https://github.com/JacopoPan/gym-pybullet-drones/blob/master/examples/run_learning.py) for an example +Or using `gym.make()`—see [`sa_learning.py`](https://github.com/JacopoPan/gym-pybullet-drones/blob/master/examples/sa_learning.py) for an example ``` ->>> env = gym.make('single-drone-v0') # See run_learning_test.py +>>> env = gym.make('single-drone-v0') # See sa_learning.py ``` Then, the environment can be stepped with ``` @@ -167,7 +167,7 @@ The halting conditions can/should be modified in class [`SingleDroneUserDefinedF ### Drag and Ground Effect Models -Simple drag and ground effect models can be included in the simulation initializing `SingleDroneEnv()` with `aero_effects=True`, these are based on the system identification of [Forster (2015)](http://mikehamer.info/assets/papers/Crazyflie%20Modelling.pdf) (see Ch. 4) +Simple drag and ground effect models can be included in the simulation initializing `SingleDroneEnv()` with `aero_effects=True`, these are based on the system identification of [Forster (2015)](http://mikehamer.info/assets/papers/Crazyflie%20Modelling.pdf) (see Eq. 4.2) and the analytical model used as a baseline for comparison by [Shi et al. (2019)](https://arxiv.org/pdf/1811.08027.pdf) (see Eq. 15) Check the implementation of `_simpleAerodynamicEffects()` in class [`SingleDroneEnv`](https://github.com/JacopoPan/gym-pybullet-drones/blob/master/gym_pybullet_drones/envs/SingleDroneEnv.py) for more detail @@ -176,7 +176,7 @@ Check the implementation of `_simpleAerodynamicEffects()` in class [`SingleDrone ## MultiDroneEnv -WIP +A multi-agent extension of SingleDroneEnv (WIP) ### Actions ... ### Observation Space @@ -195,14 +195,20 @@ WIP -## VelocitySwarmEnv +## Simpler Environments for Swarm Applications WIP -## PointMassSwarmEnv -WIP +### PointMassSwarmEnv +A multi-agent environment with simplifed dynamics, using point-mass models (WIP) + + + + +### VelocitySwarmEnv +A multi-agent environment without dynamics, where velocities can be arbitrarily set (WIP) diff --git a/examples/run_flight.py b/examples/sa_flight.py similarity index 100% rename from examples/run_flight.py rename to examples/sa_flight.py diff --git a/examples/run_learning.py b/examples/sa_learning.py similarity index 100% rename from examples/run_learning.py rename to examples/sa_learning.py diff --git a/examples/run_trace.py b/examples/sa_trace.py similarity index 100% rename from examples/run_trace.py rename to examples/sa_trace.py diff --git a/gym_pybullet_drones/control/SingleDroneControl.py b/gym_pybullet_drones/control/SingleDroneControl.py index d83f58d7a..f5f0add15 100644 --- a/gym_pybullet_drones/control/SingleDroneControl.py +++ b/gym_pybullet_drones/control/SingleDroneControl.py @@ -99,11 +99,6 @@ def computeControl(self, control_timestep, cur_pos, cur_quat_rpy, cur_vel, cur_a return rpm, pos_err, computed_target_rpy[2]-cur_rpy[2] else: print("[ERROR] ctrl it:", self.control_counter, "ControlleType not yet implemented") - -###################################################################################################################################################### -#### Internals ####################################################################################################################################### -###################################################################################################################################################### - #################################################################################################### #### Generic PID position control (with yaw locked to 0.) ########################################## #################################################################################################### diff --git a/gym_pybullet_drones/envs/MultiDroneEnv.py b/gym_pybullet_drones/envs/MultiDroneEnv.py index ae1e13c93..50978a41b 100644 --- a/gym_pybullet_drones/envs/MultiDroneEnv.py +++ b/gym_pybullet_drones/envs/MultiDroneEnv.py @@ -50,11 +50,6 @@ def render(self, mode='human', close=False): def close(self): pass - -###################################################################################################################################################### -#### Internals ####################################################################################################################################### -###################################################################################################################################################### - #################################################################################################### #### TBD ########################################################################################### #################################################################################################### diff --git a/gym_pybullet_drones/envs/SingleDroneEnv.py b/gym_pybullet_drones/envs/SingleDroneEnv.py index 924f0c957..79f12a78d 100644 --- a/gym_pybullet_drones/envs/SingleDroneEnv.py +++ b/gym_pybullet_drones/envs/SingleDroneEnv.py @@ -243,11 +243,6 @@ def getPyBulletClient(self): def getDroneId(self): return self.DRONE_ID - -###################################################################################################################################################### -#### Internals ####################################################################################################################################### -###################################################################################################################################################### - #################################################################################################### #### Denormalize the [-1,1] range to the [0, MAX RPM] range ######################################## ####################################################################################################