jaxsim 0.1.dev401__py3-none-any.whl → 0.2.0__py3-none-any.whl

This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.
Files changed (89) hide show
  1. jaxsim/__init__.py +5 -6
  2. jaxsim/_version.py +2 -2
  3. jaxsim/api/__init__.py +3 -0
  4. jaxsim/api/com.py +240 -0
  5. jaxsim/api/common.py +216 -0
  6. jaxsim/api/contact.py +271 -0
  7. jaxsim/api/data.py +821 -0
  8. jaxsim/api/joint.py +189 -0
  9. jaxsim/api/kin_dyn_parameters.py +777 -0
  10. jaxsim/api/link.py +361 -0
  11. jaxsim/api/model.py +1633 -0
  12. jaxsim/api/ode.py +295 -0
  13. jaxsim/api/ode_data.py +694 -0
  14. jaxsim/api/references.py +421 -0
  15. jaxsim/integrators/__init__.py +2 -0
  16. jaxsim/integrators/common.py +594 -0
  17. jaxsim/integrators/fixed_step.py +102 -0
  18. jaxsim/integrators/variable_step.py +610 -0
  19. jaxsim/math/__init__.py +11 -0
  20. jaxsim/math/adjoint.py +24 -2
  21. jaxsim/math/joint_model.py +335 -0
  22. jaxsim/math/quaternion.py +44 -3
  23. jaxsim/math/rotation.py +4 -4
  24. jaxsim/math/transform.py +92 -0
  25. jaxsim/mujoco/__init__.py +3 -0
  26. jaxsim/mujoco/__main__.py +192 -0
  27. jaxsim/mujoco/loaders.py +615 -0
  28. jaxsim/mujoco/model.py +414 -0
  29. jaxsim/mujoco/visualizer.py +176 -0
  30. jaxsim/parsers/descriptions/collision.py +14 -0
  31. jaxsim/parsers/descriptions/link.py +13 -2
  32. jaxsim/parsers/kinematic_graph.py +8 -3
  33. jaxsim/parsers/rod/parser.py +54 -38
  34. jaxsim/parsers/rod/utils.py +7 -8
  35. jaxsim/rbda/__init__.py +7 -0
  36. jaxsim/rbda/aba.py +295 -0
  37. jaxsim/rbda/collidable_points.py +142 -0
  38. jaxsim/{physics/algos → rbda}/crba.py +43 -42
  39. jaxsim/rbda/forward_kinematics.py +113 -0
  40. jaxsim/rbda/jacobian.py +201 -0
  41. jaxsim/rbda/rnea.py +237 -0
  42. jaxsim/rbda/soft_contacts.py +296 -0
  43. jaxsim/rbda/utils.py +152 -0
  44. jaxsim/terrain/__init__.py +2 -0
  45. jaxsim/{physics/algos → terrain}/terrain.py +4 -6
  46. jaxsim/typing.py +30 -30
  47. jaxsim/utils/__init__.py +1 -4
  48. jaxsim/utils/hashless.py +18 -0
  49. jaxsim/utils/jaxsim_dataclass.py +281 -31
  50. {jaxsim-0.1.dev401.dist-info → jaxsim-0.2.0.dist-info}/LICENSE +1 -1
  51. jaxsim-0.2.0.dist-info/METADATA +237 -0
  52. jaxsim-0.2.0.dist-info/RECORD +64 -0
  53. {jaxsim-0.1.dev401.dist-info → jaxsim-0.2.0.dist-info}/WHEEL +1 -1
  54. jaxsim/high_level/__init__.py +0 -2
  55. jaxsim/high_level/common.py +0 -11
  56. jaxsim/high_level/joint.py +0 -148
  57. jaxsim/high_level/link.py +0 -259
  58. jaxsim/high_level/model.py +0 -1695
  59. jaxsim/math/conv.py +0 -114
  60. jaxsim/math/joint.py +0 -101
  61. jaxsim/math/plucker.py +0 -100
  62. jaxsim/physics/__init__.py +0 -12
  63. jaxsim/physics/algos/__init__.py +0 -0
  64. jaxsim/physics/algos/aba.py +0 -256
  65. jaxsim/physics/algos/aba_motors.py +0 -284
  66. jaxsim/physics/algos/forward_kinematics.py +0 -79
  67. jaxsim/physics/algos/jacobian.py +0 -98
  68. jaxsim/physics/algos/rnea.py +0 -180
  69. jaxsim/physics/algos/rnea_motors.py +0 -196
  70. jaxsim/physics/algos/soft_contacts.py +0 -454
  71. jaxsim/physics/algos/utils.py +0 -69
  72. jaxsim/physics/model/__init__.py +0 -0
  73. jaxsim/physics/model/ground_contact.py +0 -55
  74. jaxsim/physics/model/physics_model.py +0 -358
  75. jaxsim/physics/model/physics_model_state.py +0 -174
  76. jaxsim/simulation/__init__.py +0 -4
  77. jaxsim/simulation/integrators.py +0 -452
  78. jaxsim/simulation/ode.py +0 -290
  79. jaxsim/simulation/ode_data.py +0 -53
  80. jaxsim/simulation/ode_integration.py +0 -125
  81. jaxsim/simulation/simulator.py +0 -544
  82. jaxsim/simulation/simulator_callbacks.py +0 -53
  83. jaxsim/simulation/utils.py +0 -15
  84. jaxsim/sixd/__init__.py +0 -2
  85. jaxsim/utils/oop.py +0 -532
  86. jaxsim/utils/vmappable.py +0 -117
  87. jaxsim-0.1.dev401.dist-info/METADATA +0 -167
  88. jaxsim-0.1.dev401.dist-info/RECORD +0 -64
  89. {jaxsim-0.1.dev401.dist-info → jaxsim-0.2.0.dist-info}/top_level.txt +0 -0
@@ -0,0 +1,615 @@
1
+ import dataclasses
2
+ import pathlib
3
+ import tempfile
4
+ import warnings
5
+ from typing import Any
6
+
7
+ import mujoco as mj
8
+ import rod.urdf.exporter
9
+ from lxml import etree as ET
10
+
11
+
12
+ def load_rod_model(
13
+ model_description: str | pathlib.Path | rod.Model,
14
+ is_urdf: bool | None = None,
15
+ model_name: str | None = None,
16
+ ) -> rod.Model:
17
+ """
18
+ Loads a ROD model from a URDF/SDF file or a ROD model.
19
+
20
+ Args:
21
+ model_description: The URDF/SDF file or ROD model to load.
22
+ is_urdf: Whether the model description is a URDF file.
23
+ model_name: The name of the model to load from the resource.
24
+
25
+ Returns:
26
+ rod.Model: The loaded ROD model.
27
+ """
28
+
29
+ # Parse the SDF resource.
30
+ sdf_element = rod.Sdf.load(sdf=model_description, is_urdf=is_urdf)
31
+
32
+ # Fail if the SDF resource has no model.
33
+ if len(sdf_element.models()) == 0:
34
+ raise RuntimeError("Failed to find any model in the model description")
35
+
36
+ # Return the model if there is only one.
37
+ if len(sdf_element.models()) == 1:
38
+ if model_name is not None and sdf_element.models()[0].name != model_name:
39
+ raise ValueError(f"Model '{model_name}' not found in the description")
40
+
41
+ return sdf_element.models()[0]
42
+
43
+ # Require users to specify the model name if there are multiple models.
44
+ if model_name is None:
45
+ msg = "The resource has multiple models. Please specify the model name."
46
+ raise ValueError(msg)
47
+
48
+ # Build a dictionary of models in the resource for easy access.
49
+ models = {m.name: m for m in sdf_element.models()}
50
+
51
+ if model_name not in models:
52
+ raise ValueError(f"Model '{model_name}' not found in the resource")
53
+
54
+ return models[model_name]
55
+
56
+
57
+ class RodModelToMjcf:
58
+ """"""
59
+
60
+ @staticmethod
61
+ def assets_from_rod_model(
62
+ rod_model: rod.Model,
63
+ ) -> dict[str, bytes]:
64
+ """
65
+ Generates a dictionary of assets from a ROD model.
66
+
67
+ Args:
68
+ rod_model: The ROD model to extract the assets from.
69
+
70
+ Returns:
71
+ dict: A dictionary of assets.
72
+ """
73
+
74
+ import resolve_robotics_uri_py
75
+
76
+ assets_files = dict()
77
+
78
+ for link in rod_model.links():
79
+ for visual in link.visuals():
80
+ if visual.geometry.mesh and visual.geometry.mesh.uri:
81
+ assets_files[visual.geometry.mesh.uri] = (
82
+ resolve_robotics_uri_py.resolve_robotics_uri(
83
+ visual.geometry.mesh.uri
84
+ )
85
+ )
86
+
87
+ for collision in link.collisions():
88
+ if collision.geometry.mesh and collision.geometry.mesh.uri:
89
+ assets_files[collision.geometry.mesh.uri] = (
90
+ resolve_robotics_uri_py.resolve_robotics_uri(
91
+ collision.geometry.mesh.uri
92
+ )
93
+ )
94
+
95
+ assets = {
96
+ asset_name: asset.read_bytes() for asset_name, asset in assets_files.items()
97
+ }
98
+
99
+ return assets
100
+
101
+ @staticmethod
102
+ def add_floating_joint(
103
+ urdf_string: str,
104
+ base_link_name: str,
105
+ floating_joint_name: str = "world_to_base",
106
+ ) -> str:
107
+ """
108
+ Adds a floating joint to a URDF string.
109
+
110
+ Args:
111
+ urdf_string: The URDF string to modify.
112
+ base_link_name: The name of the base link to attach the floating joint.
113
+ floating_joint_name: The name of the floating joint to add.
114
+
115
+ Returns:
116
+ str: The modified URDF string.
117
+ """
118
+
119
+ with tempfile.NamedTemporaryFile(mode="w+", suffix=".urdf") as urdf_file:
120
+
121
+ # Write the URDF string to a temporary file and move current position
122
+ # to the beginning.
123
+ urdf_file.write(urdf_string)
124
+ urdf_file.seek(0)
125
+
126
+ # Parse the MJCF string as XML (etree).
127
+ parser = ET.XMLParser(remove_blank_text=True)
128
+ tree = ET.parse(source=urdf_file, parser=parser)
129
+
130
+ root: ET._Element = tree.getroot()
131
+
132
+ if root.find(f".//joint[@name='{floating_joint_name}']") is not None:
133
+ msg = f"The URDF already has a floating joint '{floating_joint_name}'"
134
+ warnings.warn(msg, stacklevel=2)
135
+ return ET.tostring(root, pretty_print=True).decode()
136
+
137
+ # Create the "world" link if it doesn't exist.
138
+ if root.find(".//link[@name='world']") is None:
139
+ _ = ET.SubElement(root, "link", name="world")
140
+
141
+ # Create the floating joint.
142
+ world_to_base = ET.SubElement(
143
+ root, "joint", name=floating_joint_name, type="floating"
144
+ )
145
+
146
+ # Check that the base link exists.
147
+ if root.find(f".//link[@name='{base_link_name}']") is None:
148
+ raise ValueError(f"Link '{base_link_name}' not found in the URDF")
149
+
150
+ # Attach the floating joint to the base link.
151
+ ET.SubElement(world_to_base, "parent", link="world")
152
+ ET.SubElement(world_to_base, "child", link=base_link_name)
153
+
154
+ urdf_string = ET.tostring(root, pretty_print=True).decode()
155
+ return urdf_string
156
+
157
+ @staticmethod
158
+ def convert(
159
+ rod_model: rod.Model,
160
+ considered_joints: list[str] | None = None,
161
+ plane_normal: tuple[float, float, float] = (0, 0, 1),
162
+ heightmap: bool | None = None,
163
+ cameras: list[dict[str, str]] | dict[str, str] = None,
164
+ ) -> tuple[str, dict[str, Any]]:
165
+ """
166
+ Converts a ROD model to a Mujoco MJCF string.
167
+
168
+ Args:
169
+ rod_model: The ROD model to convert.
170
+ considered_joints: The list of joint names to consider in the conversion.
171
+ plane_normal: The normal vector of the plane.
172
+ heightmap: Whether to generate a heightmap.
173
+ cameras: The list of cameras to add to the scene.
174
+
175
+ Returns:
176
+ tuple: A tuple containing the MJCF string and the assets dictionary.
177
+ """
178
+
179
+ # -------------------------------------
180
+ # Convert the model description to URDF
181
+ # -------------------------------------
182
+
183
+ # Consider all joints if not specified otherwise.
184
+ considered_joints = set(
185
+ considered_joints
186
+ if considered_joints is not None
187
+ else [j.name for j in rod_model.joints() if j.type != "fixed"]
188
+ )
189
+
190
+ # If considered joints are passed, make sure that they are all part of the model.
191
+ if considered_joints - set([j.name for j in rod_model.joints()]):
192
+ extra_joints = set(considered_joints) - set(
193
+ [j.name for j in rod_model.joints()]
194
+ )
195
+ msg = f"Couldn't find the following joints in the model: '{extra_joints}'"
196
+ raise ValueError(msg)
197
+
198
+ # Create a dictionary of joints for quick access.
199
+ joints_dict = {j.name: j for j in rod_model.joints()}
200
+
201
+ # Convert all the joints not considered to fixed joints.
202
+ for joint_name in set(j.name for j in rod_model.joints()) - considered_joints:
203
+ joints_dict[joint_name].type = "fixed"
204
+
205
+ # Convert the ROD model to URDF.
206
+ urdf_string = rod.urdf.exporter.UrdfExporter.sdf_to_urdf_string(
207
+ sdf=rod.Sdf(model=rod_model, version="1.7"),
208
+ gazebo_preserve_fixed_joints=False,
209
+ pretty=True,
210
+ )
211
+
212
+ # -------------------------------------
213
+ # Add a floating joint if floating-base
214
+ # -------------------------------------
215
+
216
+ if not rod_model.is_fixed_base():
217
+ considered_joints |= {"world_to_base"}
218
+ urdf_string = RodModelToMjcf.add_floating_joint(
219
+ urdf_string=urdf_string,
220
+ base_link_name=rod_model.get_canonical_link(),
221
+ floating_joint_name="world_to_base",
222
+ )
223
+
224
+ # ---------------------------------------
225
+ # Inject the <mujoco> element in the URDF
226
+ # ---------------------------------------
227
+
228
+ parser = ET.XMLParser(remove_blank_text=True)
229
+ root = ET.fromstring(text=urdf_string.encode(), parser=parser)
230
+
231
+ mujoco_element = (
232
+ ET.SubElement(root, "mujoco")
233
+ if len(root.findall("./mujoco")) == 0
234
+ else root.find("./mujoco")
235
+ )
236
+
237
+ _ = ET.SubElement(
238
+ mujoco_element,
239
+ "compiler",
240
+ balanceinertia="true",
241
+ discardvisual="false",
242
+ )
243
+
244
+ urdf_string = ET.tostring(root, pretty_print=True).decode()
245
+
246
+ # ------------------------------
247
+ # Post-process all dummy visuals
248
+ # ------------------------------
249
+
250
+ parser = ET.XMLParser(remove_blank_text=True)
251
+ root: ET._Element = ET.fromstring(text=urdf_string.encode(), parser=parser)
252
+ import numpy as np
253
+
254
+ # Give a tiny radius to all dummy spheres
255
+ for geometry in root.findall(".//visual/geometry[sphere]"):
256
+ radius = np.fromstring(
257
+ geometry.find("./sphere").attrib["radius"], sep=" ", dtype=float
258
+ )
259
+ if np.allclose(radius, np.zeros(1)):
260
+ geometry.find("./sphere").set("radius", "0.001")
261
+
262
+ # Give a tiny volume to all dummy boxes
263
+ for geometry in root.findall(".//visual/geometry[box]"):
264
+ size = np.fromstring(
265
+ geometry.find("./box").attrib["size"], sep=" ", dtype=float
266
+ )
267
+ if np.allclose(size, np.zeros(3)):
268
+ geometry.find("./box").set("size", "0.001 0.001 0.001")
269
+
270
+ urdf_string = ET.tostring(root, pretty_print=True).decode()
271
+
272
+ # ------------------------
273
+ # Convert the URDF to MJCF
274
+ # ------------------------
275
+
276
+ # Load the URDF model into Mujoco.
277
+ assets = RodModelToMjcf.assets_from_rod_model(rod_model=rod_model)
278
+ mj_model = mj.MjModel.from_xml_string(xml=urdf_string, assets=assets) # noqa
279
+
280
+ # Get the joint names.
281
+ mj_joint_names = set(
282
+ mj.mj_id2name(mj_model, mj.mjtObj.mjOBJ_JOINT, idx)
283
+ for idx in range(mj_model.njnt)
284
+ )
285
+
286
+ # Check that the Mujoco model only has the considered joints.
287
+ if mj_joint_names != considered_joints:
288
+ extra1 = mj_joint_names - considered_joints
289
+ extra2 = considered_joints - mj_joint_names
290
+ extra_joints = extra1.union(extra2)
291
+ msg = "The Mujoco model has the following extra/missing joints: '{}'"
292
+ raise ValueError(msg.format(extra_joints))
293
+
294
+ with tempfile.NamedTemporaryFile(
295
+ mode="w+", suffix=".xml", prefix=f"{rod_model.name}_"
296
+ ) as mjcf_file:
297
+
298
+ # Convert the in-memory Mujoco model to MJCF.
299
+ mj.mj_saveLastXML(mjcf_file.name, mj_model)
300
+
301
+ # Parse the MJCF string as XML (etree).
302
+ # We need to post-process the file to include additional elements.
303
+ parser = ET.XMLParser(remove_blank_text=True)
304
+ tree = ET.parse(source=mjcf_file, parser=parser)
305
+
306
+ # Get the root element.
307
+ root: ET._Element = tree.getroot()
308
+
309
+ # Find the <mujoco> element (might be the root itself).
310
+ mujoco_element: ET._Element = list(root.iter("mujoco"))[0]
311
+
312
+ # --------------
313
+ # Add the motors
314
+ # --------------
315
+
316
+ if len(mujoco_element.findall(".//actuator")) > 0:
317
+ raise RuntimeError("The model already has <actuator> elements.")
318
+
319
+ # Add the actuator element.
320
+ actuator_element = ET.SubElement(mujoco_element, "actuator")
321
+
322
+ # Add a motor for each joint.
323
+ for joint_element in mujoco_element.findall(".//joint"):
324
+ assert (
325
+ joint_element.attrib["name"] in considered_joints
326
+ ), joint_element.attrib["name"]
327
+ if joint_element.attrib.get("type", "hinge") in {"free", "ball"}:
328
+ continue
329
+ ET.SubElement(
330
+ actuator_element,
331
+ "motor",
332
+ name=f"{joint_element.attrib['name']}_motor",
333
+ joint=joint_element.attrib["name"],
334
+ gear="1",
335
+ )
336
+
337
+ # ---------------------------------------------
338
+ # Set full transparency of collision geometries
339
+ # ---------------------------------------------
340
+
341
+ parser = ET.XMLParser(remove_blank_text=True)
342
+
343
+ # Get all the (optional) names of the URDF collision elements
344
+ collision_names = {
345
+ c.attrib["name"]
346
+ for c in ET.fromstring(text=urdf_string.encode(), parser=parser).findall(
347
+ ".//collision[geometry]"
348
+ )
349
+ if "name" in c.attrib
350
+ }
351
+
352
+ # Set alpha=0 to the color of all collision elements
353
+ for geometry_element in mujoco_element.findall(".//geom[@rgba]"):
354
+ if geometry_element.attrib.get("name") in collision_names:
355
+ r, g, b, a = geometry_element.attrib["rgba"].split(" ")
356
+ geometry_element.set("rgba", f"{r} {g} {b} 0")
357
+
358
+ # -----------------------
359
+ # Create the scene assets
360
+ # -----------------------
361
+
362
+ asset_element = (
363
+ ET.SubElement(mujoco_element, "asset")
364
+ if len(mujoco_element.findall(".//asset")) == 0
365
+ else mujoco_element.find(".//asset")
366
+ )
367
+
368
+ _ = ET.SubElement(
369
+ asset_element,
370
+ "texture",
371
+ type="skybox",
372
+ builtin="gradient",
373
+ rgb1="0.3 0.5 0.7",
374
+ rgb2="0 0 0",
375
+ width="512",
376
+ height="512",
377
+ )
378
+
379
+ _ = ET.SubElement(
380
+ asset_element,
381
+ "texture",
382
+ name="plane_texture",
383
+ type="2d",
384
+ builtin="checker",
385
+ rgb1="0.1 0.2 0.3",
386
+ rgb2="0.2 0.3 0.4",
387
+ width="512",
388
+ height="512",
389
+ mark="cross",
390
+ markrgb=".8 .8 .8",
391
+ )
392
+
393
+ _ = ET.SubElement(
394
+ asset_element,
395
+ "material",
396
+ name="plane_material",
397
+ texture="plane_texture",
398
+ reflectance="0.2",
399
+ texrepeat="5 5",
400
+ texuniform="true",
401
+ )
402
+
403
+ _ = (
404
+ ET.SubElement(
405
+ asset_element,
406
+ "hfield",
407
+ name="terrain",
408
+ nrow="100",
409
+ ncol="100",
410
+ size="5 5 1 1",
411
+ )
412
+ if heightmap
413
+ else None
414
+ )
415
+
416
+ # ----------------------------------
417
+ # Populate the scene with the assets
418
+ # ----------------------------------
419
+
420
+ worldbody_scene_element = ET.SubElement(mujoco_element, "worldbody")
421
+
422
+ _ = ET.SubElement(
423
+ worldbody_scene_element,
424
+ "geom",
425
+ name="floor",
426
+ type="plane" if not heightmap else "hfield",
427
+ size="0 0 0.05",
428
+ material="plane_material",
429
+ condim="3",
430
+ contype="1",
431
+ conaffinity="1",
432
+ zaxis=" ".join(map(str, plane_normal)),
433
+ **({"hfield": "terrain"} if heightmap else {}),
434
+ )
435
+
436
+ _ = ET.SubElement(
437
+ worldbody_scene_element,
438
+ "light",
439
+ name="sun",
440
+ mode="fixed",
441
+ directional="true",
442
+ castshadow="true",
443
+ pos="0 0 10",
444
+ dir="0 0 -1",
445
+ )
446
+
447
+ # -------------------------------------------------------
448
+ # Add a camera following the CoM of the worldbody element
449
+ # -------------------------------------------------------
450
+
451
+ worldbody_element = None
452
+
453
+ # Find the <worldbody> element of our model by searching the one that contains
454
+ # all the considered joints. This is needed because there might be multiple
455
+ # <worldbody> elements inside <mujoco>.
456
+ for wb in mujoco_element.findall(".//worldbody"):
457
+ if all(
458
+ wb.find(f".//joint[@name='{j}']") is not None for j in considered_joints
459
+ ):
460
+ worldbody_element = wb
461
+ break
462
+
463
+ if worldbody_element is None:
464
+ raise RuntimeError("Failed to find the <worldbody> element of the model")
465
+
466
+ # Camera attached to the model
467
+ # It can be manually copied from `python -m mujoco.viewer --mjcf=<URDF_PATH>`
468
+ _ = ET.SubElement(
469
+ worldbody_element,
470
+ "camera",
471
+ name="track",
472
+ mode="trackcom",
473
+ pos="1.930 -2.279 0.556",
474
+ xyaxes="0.771 0.637 0.000 -0.116 0.140 0.983",
475
+ fovy="60",
476
+ )
477
+
478
+ # Add user-defined camera
479
+ cameras = cameras if cameras is not None else {}
480
+ for camera in cameras if isinstance(cameras, list) else [cameras]:
481
+ mj_camera = MujocoCamera.build(**camera)
482
+ _ = ET.SubElement(
483
+ worldbody_element, "camera", dataclasses.asdict(mj_camera)
484
+ )
485
+
486
+ # ------------------------------------------------
487
+ # Add a light following the CoM of the first link
488
+ # ------------------------------------------------
489
+
490
+ if not rod_model.is_fixed_base():
491
+
492
+ # Light attached to the model
493
+ _ = ET.SubElement(
494
+ worldbody_element,
495
+ "light",
496
+ name="light_model",
497
+ mode="targetbodycom",
498
+ target=worldbody_element.find(".//body").attrib["name"],
499
+ directional="false",
500
+ castshadow="true",
501
+ pos="1 0 5",
502
+ )
503
+
504
+ # --------------------------------
505
+ # Return the resulting MJCF string
506
+ # --------------------------------
507
+
508
+ mjcf_string = ET.tostring(root, pretty_print=True).decode()
509
+ return mjcf_string, assets
510
+
511
+
512
+ class UrdfToMjcf:
513
+ @staticmethod
514
+ def convert(
515
+ urdf: str | pathlib.Path,
516
+ considered_joints: list[str] | None = None,
517
+ model_name: str | None = None,
518
+ plane_normal: tuple[float, float, float] = (0, 0, 1),
519
+ heightmap: bool | None = None,
520
+ cameras: list[dict[str, str]] | dict[str, str] = None,
521
+ ) -> tuple[str, dict[str, Any]]:
522
+ """
523
+ Converts a URDF file to a Mujoco MJCF string.
524
+
525
+ Args:
526
+ urdf: The URDF file to convert.
527
+ considered_joints: The list of joint names to consider in the conversion.
528
+ model_name: The name of the model to convert.
529
+ plane_normal: The normal vector of the plane.
530
+ heightmap: Whether to generate a heightmap.
531
+ cameras: The list of cameras to add to the scene.
532
+
533
+ Returns:
534
+ tuple: A tuple containing the MJCF string and the assets dictionary.
535
+ """
536
+
537
+ # Get the ROD model.
538
+ rod_model = load_rod_model(
539
+ model_description=urdf,
540
+ is_urdf=True,
541
+ model_name=model_name,
542
+ )
543
+
544
+ # Convert the ROD model to MJCF.
545
+ return RodModelToMjcf.convert(
546
+ rod_model=rod_model,
547
+ considered_joints=considered_joints,
548
+ plane_normal=plane_normal,
549
+ heightmap=heightmap,
550
+ cameras=cameras,
551
+ )
552
+
553
+
554
+ class SdfToMjcf:
555
+ @staticmethod
556
+ def convert(
557
+ sdf: str | pathlib.Path,
558
+ considered_joints: list[str] | None = None,
559
+ model_name: str | None = None,
560
+ plane_normal: tuple[float, float, float] = (0, 0, 1),
561
+ heightmap: bool | None = None,
562
+ cameras: list[dict[str, str]] | dict[str, str] = None,
563
+ ) -> tuple[str, dict[str, Any]]:
564
+ """
565
+ Converts a SDF file to a Mujoco MJCF string.
566
+
567
+ Args:
568
+ sdf: The SDF file to convert.
569
+ considered_joints: The list of joint names to consider in the conversion.
570
+ model_name: The name of the model to convert.
571
+ plane_normal: The normal vector of the plane.
572
+ heightmap: Whether to generate a heightmap.
573
+ cameras: The list of cameras to add to the scene.
574
+
575
+ Returns:
576
+ tuple: A tuple containing the MJCF string and the assets dictionary.
577
+ """
578
+
579
+ # Get the ROD model.
580
+ rod_model = load_rod_model(
581
+ model_description=sdf,
582
+ is_urdf=False,
583
+ model_name=model_name,
584
+ )
585
+
586
+ # Convert the ROD model to MJCF.
587
+ return RodModelToMjcf.convert(
588
+ rod_model=rod_model,
589
+ considered_joints=considered_joints,
590
+ plane_normal=plane_normal,
591
+ heightmap=heightmap,
592
+ cameras=cameras,
593
+ )
594
+
595
+
596
+ @dataclasses.dataclass
597
+ class MujocoCamera:
598
+ name: str
599
+ mode: str
600
+ pos: str
601
+ xyaxes: str
602
+ fovy: str
603
+
604
+ @classmethod
605
+ def build(cls, **kwargs):
606
+ if not all(isinstance(value, str) for value in kwargs.values()):
607
+ raise ValueError("Values must be strings")
608
+
609
+ if len(kwargs["pos"].split()) != 3:
610
+ raise ValueError("pos must have three values separated by space")
611
+
612
+ if len(kwargs["xyaxes"].split()) != 6:
613
+ raise ValueError("xyaxes must have six values separated by space")
614
+
615
+ return cls(**kwargs)