Skip to content

Commit

Permalink
Changed package asset imports to use plg_resources library
Browse files Browse the repository at this point in the history
  • Loading branch information
spencerteetaert committed Jun 9, 2022
1 parent f747c9a commit efb1def
Show file tree
Hide file tree
Showing 6 changed files with 13 additions and 6 deletions.
1 change: 1 addition & 0 deletions build_project.sh
Original file line number Diff line number Diff line change
Expand Up @@ -4,4 +4,5 @@ poetry build
pip install dist/gym_pybullet_drones-1.0.0-py3-none-any.whl
cd tests
python test_build.py
rm -rf results
cd ..
4 changes: 3 additions & 1 deletion gym_pybullet_drones/control/BaseControl.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
import os
import numpy as np
import xml.etree.ElementTree as etxml
import pkg_resources

from gym_pybullet_drones.utils.enums import DroneModel

Expand Down Expand Up @@ -198,7 +199,8 @@ def _getURDFParameter(self,
"""
#### Get the XML tree of the drone model to control ########
URDF = self.DRONE_MODEL.value + ".urdf"
URDF_TREE = etxml.parse(os.path.dirname(os.path.abspath(__file__))+"/../assets/"+URDF).getroot()
path = pkg_resources.resource_filename('gym_pybullet_drones', 'assets/'+URDF)
URDF_TREE = etxml.parse(path).getroot()
#### Find and return the desired parameter #################
if parameter_name == 'm':
return float(URDF_TREE[1][0][1].attrib['value'])
Expand Down
6 changes: 4 additions & 2 deletions gym_pybullet_drones/envs/BaseAviary.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
import collections
from datetime import datetime
import xml.etree.ElementTree as etxml
import pkg_resources
from PIL import Image
# import pkgutil
# egl = pkgutil.get_loader('eglRenderer')
Expand Down Expand Up @@ -453,7 +454,8 @@ def _housekeeping(self):
p.setAdditionalSearchPath(pybullet_data.getDataPath(), physicsClientId=self.CLIENT)
#### Load ground plane, drone and obstacles models #########
self.PLANE_ID = p.loadURDF("plane.urdf", physicsClientId=self.CLIENT)
self.DRONE_IDS = np.array([p.loadURDF(os.path.dirname(os.path.abspath(__file__))+"/../assets/"+self.URDF,

self.DRONE_IDS = np.array([p.loadURDF(pkg_resources.resource_filename('gym_pybullet_drones', 'assets/'+self.URDF),
self.INIT_XYZS[i,:],
p.getQuaternionFromEuler(self.INIT_RPYS[i,:]),
flags = p.URDF_USE_INERTIA_FROM_FILE,
Expand Down Expand Up @@ -962,7 +964,7 @@ def _parseURDFParameters(self):
files in folder `assets/`.
"""
URDF_TREE = etxml.parse(os.path.dirname(os.path.abspath(__file__))+"/../assets/"+self.URDF).getroot()
URDF_TREE = etxml.parse(pkg_resources.resource_filename('gym_pybullet_drones', 'assets/'+self.URDF)).getroot()
M = float(URDF_TREE[1][0][1].attrib['value'])
L = float(URDF_TREE[0].attrib['arm'])
THRUST2WEIGHT_RATIO = float(URDF_TREE[0].attrib['thrust2weight'])
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
import os
import numpy as np
import pybullet as p
import pkg_resources

from gym_pybullet_drones.utils.enums import DroneModel, Physics
from gym_pybullet_drones.envs.single_agent_rl.BaseSingleAgentAviary import ActionType, ObservationType, BaseSingleAgentAviary
Expand Down Expand Up @@ -72,7 +73,7 @@ def _addObstacles(self):
"""
super()._addObstacles()
p.loadURDF(os.path.dirname(os.path.abspath(__file__))+"/../../assets/architrave.urdf",
p.loadURDF(pkg_resources.resource_filename('gym_pybullet_drones', 'assets/architrave.urdf'),
[0, -1, .55],
p.getQuaternionFromEuler([0, 0, 0]),
physicsClientId=self.CLIENT
Expand Down
3 changes: 2 additions & 1 deletion gym_pybullet_drones/examples/compare.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
import argparse
import pickle
import numpy as np
import pkg_resources

from gym_pybullet_drones.utils.utils import sync, str2bool
from gym_pybullet_drones.utils.enums import DroneModel, Physics
Expand All @@ -29,7 +30,7 @@
DEFAULT_PHYICS = Physics('pyb')
DEFAULT_GUI = False
DEFAULT_RECORD_VIDEO = False
DEFAULT_TRACE_FILE = os.path.dirname(os.path.abspath(__file__))+"/../assets/example_trace.pkl"
DEFAULT_TRACE_FILE = pkg_resources.resource_filename('gym_pybullet_drones', 'assets/example_trace.pkl')
DEFAULT_OUTPUT_FOLDER = 'results'

def run(
Expand Down
2 changes: 1 addition & 1 deletion setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
'stable_baselines3',
'ray[rllib]'
],
packages=setuptools.find_packages(where="gym_pybullet_drones")
packages=setuptools.find_packages(where="gym_pybullet_drones"),
package_dir={'':'gym_pybullet_drones'},
package_data={'gym_pybullet_drones': ['assets/*.*']},
long_description=long_description,
Expand Down

0 comments on commit efb1def

Please sign in to comment.