Skip to content

Commit

Permalink
Merge pull request #266 from maxspahn/fix-dm-control-meshes
Browse files Browse the repository at this point in the history
fix[mujoco]: Addresses #265. Adds tests for different mujoco examples.
  • Loading branch information
maxspahn authored Apr 24, 2024
2 parents 5ea4d0d + bf9f36b commit 56575a8
Show file tree
Hide file tree
Showing 5 changed files with 68 additions and 14 deletions.
1 change: 1 addition & 0 deletions examples/.gitignore
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
__pycache__
panda
pointRobot
xml_model
33 changes: 23 additions & 10 deletions examples/mujoco_example.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,6 @@
from gymnasium.wrappers import RecordVideo


ROBOTTYPE = 'panda'
ROBOTMODEL = 'panda_without_gripper'
ROBOTTYPE = 'pointRobot'
ROBOTMODEL = 'pointRobot'

def get_index_from_coordinates(point, mesh) -> tuple:
distances = np.linalg.norm(mesh - point, axis=3)
Expand All @@ -40,7 +36,14 @@ def evaluate_sdf(point, mesh, sdf, resolution) -> tuple:
return value, gradient


def run_generic_mujoco(n_steps: int = 1000, render: Union[str, bool] = True, goal: bool = False, obstacles: bool = False):
def run_generic_mujoco(
robot_name: str = 'panda',
robot_model: str = 'panda_without_gripper',
n_steps: int = 1000,
render: Union[str, bool] = True,
goal: bool = False,
obstacles: bool = False
):
if goal:
goal_list = [goal1]
else:
Expand Down Expand Up @@ -83,18 +86,21 @@ def run_generic_mujoco(n_steps: int = 1000, render: Union[str, bool] = True, goa
number_constraints=1,
physics_engine_name='mujoco',
)
robot_model = RobotModel(ROBOTTYPE, ROBOTMODEL)
robot_model = RobotModel(robot_name, robot_model)

xml_file = robot_model.get_xml_path()
robots = [
GenericMujocoRobot(xml_file=xml_file, mode="vel"),
]
env: GenericMujocoEnv = gym.make(
'generic-mujoco-env-v0',
if robot_name == 'pointRobot':
sensors=[lidar_sensor, full_sensor, free_space_decomp, sdf_sensor]
else:
sensors=[]
env = GenericMujocoEnv(
robots=robots,
obstacles=obstacle_list,
goals=goal_list,
sensors=[lidar_sensor, full_sensor, free_space_decomp, sdf_sensor],
sensors=sensors,
render=render,
enforce_real_time=True,
).unwrapped
Expand All @@ -120,4 +126,11 @@ def run_generic_mujoco(n_steps: int = 1000, render: Union[str, bool] = True, goa
return history

if __name__ == "__main__":
run_generic_mujoco(n_steps=int(1e3), render='human', obstacles=True, goal=True)
run_generic_mujoco(
robot_name='panda',
robot_model='panda_without_gripper',
n_steps=int(1e3),
render='human',
obstacles=True,
goal=True
)
36 changes: 34 additions & 2 deletions examples/test_examples.py
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,39 @@ def test_serialization():
from serializing_environments import run_serializing_example
blueprint_test(run_serializing_example)

def test_mujoco_example():
def test_pointRobot_mujoco_example():
from mujoco_example import run_generic_mujoco
blueprint_test(run_generic_mujoco)
def run_pointRobot_mujoco(
n_steps=int(1e3),
render='human',
obstacles=True,
goal=True
):
return run_generic_mujoco(
robot_name='pointRobot',
robot_model='pointRobot',
n_steps=n_steps,
render=render,
obstacles=obstacles,
goal=goal
)
blueprint_test(run_pointRobot_mujoco)

def test_panda_mujoco_example():
from mujoco_example import run_generic_mujoco
def run_panda_mujoco(
n_steps=int(1e3),
render='human',
obstacles=True,
goal=True
):
return run_generic_mujoco(
robot_name='panda',
robot_model='panda_without_gripper',
n_steps=n_steps,
render=render,
obstacles=obstacles,
goal=goal
)
blueprint_test(run_panda_mujoco)

2 changes: 1 addition & 1 deletion pyproject.toml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
[tool.poetry]
name = "urdfenvs"
version = "0.9.11"
version = "0.9.12"
description = "Simple simulation environment for robots, based on the urdf files."
authors = ["Max Spahn <m.spahn@tudelft.nl>"]
maintainers = [
Expand Down
10 changes: 9 additions & 1 deletion urdfenvs/generic_mujoco/generic_mujoco_env.py
Original file line number Diff line number Diff line change
Expand Up @@ -165,7 +165,15 @@ def velocity_limits(self) -> np.ndarray:
def _initialize_simulation(
self,
):
self.model = mujoco.MjModel.from_xml_string(self._model_dm.to_xml_string())

file_name = self._xml_file.split('/')[-1]
mjcf.export_with_assets(
self._model_dm,
'xml_model',
out_file_name=file_name,
)
self.model = mujoco.MjModel.from_xml_path(f'xml_model/{file_name}')


self.model.body_pos[0] = [0, 1, 1]
self.model.vis.global_.offwidth = self.width
Expand Down

0 comments on commit 56575a8

Please sign in to comment.