Skip to content

Commit

Permalink
Merge pull request #336 from ami-iit/visualizer_tests
Browse files Browse the repository at this point in the history
Add unit tests for `ModelToMjcf` conversion and fix typo in `MujocoCamera`
  • Loading branch information
flferretti authored Jan 10, 2025
2 parents 1044e24 + 4965926 commit 77f04c2
Show file tree
Hide file tree
Showing 4 changed files with 74 additions and 10 deletions.
2 changes: 1 addition & 1 deletion examples/jaxsim_for_robot_controllers.ipynb
Original file line number Diff line number Diff line change
Expand Up @@ -187,7 +187,7 @@
" in_link_frame=False,\n",
" ),\n",
" distance=3,\n",
" azimut=150,\n",
" azimuth=150,\n",
" elevation=-10,\n",
" ),\n",
")\n",
Expand Down
8 changes: 4 additions & 4 deletions src/jaxsim/mujoco/utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ def build_from_target_view(
camera_name: str,
lookat: Sequence[float | int] | npt.NDArray = (0, 0, 0),
distance: float | int | npt.NDArray = 3,
azimut: float | int | npt.NDArray = 90,
azimuth: float | int | npt.NDArray = 90,
elevation: float | int | npt.NDArray = -45,
fovy: float | int | npt.NDArray = 45,
degrees: bool = True,
Expand All @@ -170,7 +170,7 @@ def build_from_target_view(
distance:
The distance from the target point (displacement between the origins
of `T` and `C`).
azimut:
azimuth:
The rotation around z of the camera. With an angle of 0, the camera
would loot at the target point towards the positive x-axis of `T`.
elevation:
Expand All @@ -193,8 +193,8 @@ def build_from_target_view(
seq="ZX", angles=[-90, 90], degrees=True
).as_matrix()

# Process the azimut.
R_az = Rotation.from_euler(seq="Y", angles=azimut, degrees=degrees).as_matrix()
# Process the azimuth.
R_az = Rotation.from_euler(seq="Y", angles=azimuth, degrees=degrees).as_matrix()
W_H_C[0:3, 0:3] = W_H_C[0:3, 0:3] @ R_az

# Process elevation.
Expand Down
10 changes: 5 additions & 5 deletions src/jaxsim/mujoco/visualizer.py
Original file line number Diff line number Diff line change
Expand Up @@ -178,7 +178,7 @@ def open(
close_on_exit: bool = True,
lookat: Sequence[float | int] | npt.NDArray | None = None,
distance: float | int | npt.NDArray | None = None,
azimut: float | int | npt.NDArray | None = None,
azimuth: float | int | npt.NDArray | None = None,
elevation: float | int | npt.NDArray | None = None,
) -> contextlib.AbstractContextManager[mujoco.viewer.Handle]:
"""
Expand All @@ -195,7 +195,7 @@ def open(
viewer=handle,
lookat=lookat,
distance=distance,
azimut=azimut,
azimuth=azimuth,
elevation=elevation,
)

Expand All @@ -210,7 +210,7 @@ def setup_viewer_camera(
*,
lookat: Sequence[float | int] | npt.NDArray | None,
distance: float | int | npt.NDArray | None = None,
azimut: float | int | npt.NDArray | None = None,
azimuth: float | int | npt.NDArray | None = None,
elevation: float | int | npt.NDArray | None = None,
) -> mj.viewer.Handle:
"""
Expand All @@ -236,8 +236,8 @@ def setup_viewer_camera(
if distance is not None:
viewer.cam.distance = float(distance)

if azimut is not None:
viewer.cam.azimuth = float(azimut) % 360
if azimuth is not None:
viewer.cam.azimuth = float(azimuth) % 360

if elevation is not None:
viewer.cam.elevation = float(elevation)
Expand Down
64 changes: 64 additions & 0 deletions tests/test_visualizer.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,64 @@
import pytest
import rod

from jaxsim.mujoco import ModelToMjcf
from jaxsim.mujoco.loaders import MujocoCamera


@pytest.fixture
def mujoco_camera():

return MujocoCamera.build_from_target_view(
camera_name="test_camera",
lookat=(0, 0, 0),
distance=1,
azimuth=0,
elevation=0,
fovy=45,
degrees=True,
)


def test_urdf_loading(jaxsim_model_single_pendulum, mujoco_camera):
model = jaxsim_model_single_pendulum.built_from

_ = ModelToMjcf.convert(model=model, cameras=mujoco_camera)


def test_sdf_loading(jaxsim_model_single_pendulum, mujoco_camera):

model = rod.Sdf.load(sdf=jaxsim_model_single_pendulum.built_from).serialize(
pretty=True
)

_ = ModelToMjcf.convert(model=model, cameras=mujoco_camera)


def test_rod_loading(jaxsim_model_single_pendulum, mujoco_camera):

model = rod.Sdf.load(sdf=jaxsim_model_single_pendulum.built_from).models()[0]

_ = ModelToMjcf.convert(model=model, cameras=mujoco_camera)


def test_heightmap(jaxsim_model_single_pendulum, mujoco_camera):

model = rod.Sdf.load(sdf=jaxsim_model_single_pendulum.built_from).models()[0]

_ = ModelToMjcf.convert(
model=model,
cameras=mujoco_camera,
heightmap=True,
heightmap_samples_xy=(51, 51),
)


def test_inclined_plane(jaxsim_model_single_pendulum, mujoco_camera):

model = rod.Sdf.load(sdf=jaxsim_model_single_pendulum.built_from).models()[0]

_ = ModelToMjcf.convert(
model=model,
cameras=mujoco_camera,
plane_normal=(0.3, 0.3, 0.3),
)

0 comments on commit 77f04c2

Please sign in to comment.