Skip to content

Commit 77f04c2

Browse files
authored
Merge pull request #336 from ami-iit/visualizer_tests
Add unit tests for `ModelToMjcf` conversion and fix typo in `MujocoCamera`
2 parents 1044e24 + 4965926 commit 77f04c2

File tree

4 files changed

+74
-10
lines changed

4 files changed

+74
-10
lines changed

examples/jaxsim_for_robot_controllers.ipynb

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -187,7 +187,7 @@
187187
" in_link_frame=False,\n",
188188
" ),\n",
189189
" distance=3,\n",
190-
" azimut=150,\n",
190+
" azimuth=150,\n",
191191
" elevation=-10,\n",
192192
" ),\n",
193193
")\n",

src/jaxsim/mujoco/utils.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -147,7 +147,7 @@ def build_from_target_view(
147147
camera_name: str,
148148
lookat: Sequence[float | int] | npt.NDArray = (0, 0, 0),
149149
distance: float | int | npt.NDArray = 3,
150-
azimut: float | int | npt.NDArray = 90,
150+
azimuth: float | int | npt.NDArray = 90,
151151
elevation: float | int | npt.NDArray = -45,
152152
fovy: float | int | npt.NDArray = 45,
153153
degrees: bool = True,
@@ -170,7 +170,7 @@ def build_from_target_view(
170170
distance:
171171
The distance from the target point (displacement between the origins
172172
of `T` and `C`).
173-
azimut:
173+
azimuth:
174174
The rotation around z of the camera. With an angle of 0, the camera
175175
would loot at the target point towards the positive x-axis of `T`.
176176
elevation:
@@ -193,8 +193,8 @@ def build_from_target_view(
193193
seq="ZX", angles=[-90, 90], degrees=True
194194
).as_matrix()
195195

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

200200
# Process elevation.

src/jaxsim/mujoco/visualizer.py

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -178,7 +178,7 @@ def open(
178178
close_on_exit: bool = True,
179179
lookat: Sequence[float | int] | npt.NDArray | None = None,
180180
distance: float | int | npt.NDArray | None = None,
181-
azimut: float | int | npt.NDArray | None = None,
181+
azimuth: float | int | npt.NDArray | None = None,
182182
elevation: float | int | npt.NDArray | None = None,
183183
) -> contextlib.AbstractContextManager[mujoco.viewer.Handle]:
184184
"""
@@ -195,7 +195,7 @@ def open(
195195
viewer=handle,
196196
lookat=lookat,
197197
distance=distance,
198-
azimut=azimut,
198+
azimuth=azimuth,
199199
elevation=elevation,
200200
)
201201

@@ -210,7 +210,7 @@ def setup_viewer_camera(
210210
*,
211211
lookat: Sequence[float | int] | npt.NDArray | None,
212212
distance: float | int | npt.NDArray | None = None,
213-
azimut: float | int | npt.NDArray | None = None,
213+
azimuth: float | int | npt.NDArray | None = None,
214214
elevation: float | int | npt.NDArray | None = None,
215215
) -> mj.viewer.Handle:
216216
"""
@@ -236,8 +236,8 @@ def setup_viewer_camera(
236236
if distance is not None:
237237
viewer.cam.distance = float(distance)
238238

239-
if azimut is not None:
240-
viewer.cam.azimuth = float(azimut) % 360
239+
if azimuth is not None:
240+
viewer.cam.azimuth = float(azimuth) % 360
241241

242242
if elevation is not None:
243243
viewer.cam.elevation = float(elevation)

tests/test_visualizer.py

Lines changed: 64 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,64 @@
1+
import pytest
2+
import rod
3+
4+
from jaxsim.mujoco import ModelToMjcf
5+
from jaxsim.mujoco.loaders import MujocoCamera
6+
7+
8+
@pytest.fixture
9+
def mujoco_camera():
10+
11+
return MujocoCamera.build_from_target_view(
12+
camera_name="test_camera",
13+
lookat=(0, 0, 0),
14+
distance=1,
15+
azimuth=0,
16+
elevation=0,
17+
fovy=45,
18+
degrees=True,
19+
)
20+
21+
22+
def test_urdf_loading(jaxsim_model_single_pendulum, mujoco_camera):
23+
model = jaxsim_model_single_pendulum.built_from
24+
25+
_ = ModelToMjcf.convert(model=model, cameras=mujoco_camera)
26+
27+
28+
def test_sdf_loading(jaxsim_model_single_pendulum, mujoco_camera):
29+
30+
model = rod.Sdf.load(sdf=jaxsim_model_single_pendulum.built_from).serialize(
31+
pretty=True
32+
)
33+
34+
_ = ModelToMjcf.convert(model=model, cameras=mujoco_camera)
35+
36+
37+
def test_rod_loading(jaxsim_model_single_pendulum, mujoco_camera):
38+
39+
model = rod.Sdf.load(sdf=jaxsim_model_single_pendulum.built_from).models()[0]
40+
41+
_ = ModelToMjcf.convert(model=model, cameras=mujoco_camera)
42+
43+
44+
def test_heightmap(jaxsim_model_single_pendulum, mujoco_camera):
45+
46+
model = rod.Sdf.load(sdf=jaxsim_model_single_pendulum.built_from).models()[0]
47+
48+
_ = ModelToMjcf.convert(
49+
model=model,
50+
cameras=mujoco_camera,
51+
heightmap=True,
52+
heightmap_samples_xy=(51, 51),
53+
)
54+
55+
56+
def test_inclined_plane(jaxsim_model_single_pendulum, mujoco_camera):
57+
58+
model = rod.Sdf.load(sdf=jaxsim_model_single_pendulum.built_from).models()[0]
59+
60+
_ = ModelToMjcf.convert(
61+
model=model,
62+
cameras=mujoco_camera,
63+
plane_normal=(0.3, 0.3, 0.3),
64+
)

0 commit comments

Comments
 (0)