Skip to content

Commit

Permalink
Merge pull request #335 from ami-iit/generic_mjcf_loader
Browse files Browse the repository at this point in the history
Add `ModelToMjcf` class for generic model to MJCF conversion
  • Loading branch information
flferretti authored Jan 10, 2025
2 parents f6a9b95 + 059f9cb commit 1044e24
Show file tree
Hide file tree
Showing 2 changed files with 60 additions and 1 deletion.
2 changes: 1 addition & 1 deletion src/jaxsim/mujoco/__init__.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
from .loaders import RodModelToMjcf, SdfToMjcf, UrdfToMjcf
from .loaders import ModelToMjcf, RodModelToMjcf, SdfToMjcf, UrdfToMjcf
from .model import MujocoModelHelper
from .utils import mujoco_data_from_jaxsim
from .visualizer import MujocoVideoRecorder, MujocoVisualizer
59 changes: 59 additions & 0 deletions src/jaxsim/mujoco/loaders.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,8 @@
import rod.urdf.exporter
from lxml import etree as ET

from jaxsim import logging

from .utils import MujocoCamera

MujocoCameraType = (
Expand Down Expand Up @@ -61,6 +63,59 @@ def load_rod_model(
return models[model_name]


class ModelToMjcf:
"""
Class to convert a URDF/SDF file or a ROD model to a Mujoco MJCF string.
"""

@staticmethod
def convert(
model: str | pathlib.Path | rod.Model,
considered_joints: list[str] | None = None,
plane_normal: tuple[float, float, float] = (0, 0, 1),
heightmap: bool | None = None,
heightmap_samples_xy: tuple[int, int] = (101, 101),
cameras: MujocoCameraType = (),
) -> tuple[str, dict[str, Any]]:
"""
Convert a model to a Mujoco MJCF string.
Args:
model: The URDF/SDF file or ROD model to convert.
considered_joints: The list of joint names to consider in the conversion.
plane_normal: The normal vector of the plane.
heightmap: Whether to generate a heightmap.
heightmap_samples_xy: The number of points in the heightmap grid.
cameras: The custom cameras to add to the scene.
Returns:
A tuple containing the MJCF string and the dictionary of assets.
"""

match model:
case rod.Model():
rod_model = model
case str() | pathlib.Path():
# Convert the JaxSim model to a ROD model.
rod_model = load_rod_model(
model_description=model,
is_urdf=None,
model_name=None,
)
case _:
raise TypeError(f"Unsupported type for 'model': {type(model)}")

# Convert the ROD model to MJCF.
return RodModelToMjcf.convert(
rod_model=rod_model,
considered_joints=considered_joints,
plane_normal=plane_normal,
heightmap=heightmap,
heightmap_samples_xy=heightmap_samples_xy,
cameras=cameras,
)


class RodModelToMjcf:
"""
Class to convert a ROD model to a Mujoco MJCF string.
Expand Down Expand Up @@ -552,6 +607,8 @@ def convert(
tuple: A tuple containing the MJCF string and the assets dictionary.
"""

logging.warning("This method is deprecated. Use 'ModelToMjcf.convert' instead.")

# Get the ROD model.
rod_model = load_rod_model(
model_description=urdf,
Expand Down Expand Up @@ -598,6 +655,8 @@ def convert(
tuple: A tuple containing the MJCF string and the assets dictionary.
"""

logging.warning("This method is deprecated. Use 'ModelToMjcf.convert' instead.")

# Get the ROD model.
rod_model = load_rod_model(
model_description=sdf,
Expand Down

0 comments on commit 1044e24

Please sign in to comment.