Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Support user-defined cameras in mujoco.loaders #133

Merged
merged 2 commits into from
Apr 3, 2024
Merged
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
25 changes: 25 additions & 0 deletions src/jaxsim/mujoco/loaders.py
Original file line number Diff line number Diff line change
Expand Up @@ -159,13 +159,19 @@ def convert(
considered_joints: list[str] | None = None,
plane_normal: tuple[float, float, float] = (0, 0, 1),
heightmap: bool | None = None,
cameras: (
list[dict[str, str, str, str, str]] | dict[str, str, str, str, str]
) = None,
flferretti marked this conversation as resolved.
Show resolved Hide resolved
) -> tuple[str, dict[str, Any]]:
"""
Converts a ROD model to a Mujoco MJCF string.

Args:
rod_model: The 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.
cameras: The list of cameras to add to the scene.

Returns:
tuple: A tuple containing the MJCF string and the assets dictionary.
Expand Down Expand Up @@ -470,6 +476,11 @@ def convert(
fovy="60",
)

# Add user-defined camera
cameras = cameras if cameras is not None else {}
for camera in cameras if isinstance(cameras, list) else [cameras]:
_ = ET.SubElement(worldbody_element, "camera", **camera)

# ------------------------------------------------
# Add a light following the CoM of the first link
# ------------------------------------------------
Expand Down Expand Up @@ -504,6 +515,9 @@ def convert(
model_name: str | None = None,
plane_normal: tuple[float, float, float] = (0, 0, 1),
heightmap: bool | None = None,
cameras: (
list[dict[str, str, str, str, str]] | dict[str, str, str, str, str]
) = None,
) -> tuple[str, dict[str, Any]]:
"""
Converts a URDF file to a Mujoco MJCF string.
Expand All @@ -512,6 +526,9 @@ def convert(
urdf: The URDF file to convert.
considered_joints: The list of joint names to consider in the conversion.
model_name: The name of the model to convert.
plane_normal: The normal vector of the plane.
heightmap: Whether to generate a heightmap.
cameras: The list of cameras to add to the scene.

Returns:
tuple: A tuple containing the MJCF string and the assets dictionary.
Expand All @@ -530,6 +547,7 @@ def convert(
considered_joints=considered_joints,
plane_normal=plane_normal,
heightmap=heightmap,
cameras=cameras,
)


Expand All @@ -541,6 +559,9 @@ def convert(
model_name: str | None = None,
plane_normal: tuple[float, float, float] = (0, 0, 1),
heightmap: bool | None = None,
cameras: (
list[dict[str, str, str, str, str]] | dict[str, str, str, str, str]
) = None,
) -> tuple[str, dict[str, Any]]:
"""
Converts a SDF file to a Mujoco MJCF string.
Expand All @@ -549,6 +570,9 @@ def convert(
sdf: The SDF file to convert.
considered_joints: The list of joint names to consider in the conversion.
model_name: The name of the model to convert.
plane_normal: The normal vector of the plane.
heightmap: Whether to generate a heightmap.
cameras: The list of cameras to add to the scene.

Returns:
tuple: A tuple containing the MJCF string and the assets dictionary.
Expand All @@ -567,4 +591,5 @@ def convert(
considered_joints=considered_joints,
plane_normal=plane_normal,
heightmap=heightmap,
cameras=cameras,
)
Loading