jaxsim 0.4.3.dev97__py3-none-any.whl → 0.4.3.dev105__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.
jaxsim/_version.py CHANGED
@@ -12,5 +12,5 @@ __version__: str
12
12
  __version_tuple__: VERSION_TUPLE
13
13
  version_tuple: VERSION_TUPLE
14
14
 
15
- __version__ = version = '0.4.3.dev97'
16
- __version_tuple__ = version_tuple = (0, 4, 3, 'dev97')
15
+ __version__ = version = '0.4.3.dev105'
16
+ __version_tuple__ = version_tuple = (0, 4, 3, 'dev105')
jaxsim/api/contact.py CHANGED
@@ -208,6 +208,7 @@ def collidable_point_dynamics(
208
208
  data=data,
209
209
  link_forces=link_forces,
210
210
  joint_force_references=joint_force_references,
211
+ solver_tol=1e-3,
211
212
  )
212
213
 
213
214
  aux_data = dict()
jaxsim/api/model.py CHANGED
@@ -106,8 +106,8 @@ class JaxSimModel(JaxsimDataclass):
106
106
  terrain:
107
107
  The optional terrain to consider.
108
108
  is_urdf:
109
- Whether the model description is a URDF or an SDF. This is
110
- automatically inferred if the model description is a path to a file.
109
+ The optional flag to force the model description to be parsed as a
110
+ URDF or a SDF. This is otherwise automatically inferred.
111
111
  considered_joints:
112
112
  The list of joints to consider. If None, all joints are considered.
113
113
 
@@ -120,7 +120,7 @@ class JaxSimModel(JaxsimDataclass):
120
120
  # Parse the input resource (either a path to file or a string with the URDF/SDF)
121
121
  # and build the -intermediate- model description.
122
122
  intermediate_description = jaxsim.parsers.rod.build_model_description(
123
- model_description=model_description, is_urdf=is_urdf
123
+ model_description=model_description
124
124
  )
125
125
 
126
126
  # Lump links together if not all joints are considered.
jaxsim/mujoco/loaders.py CHANGED
@@ -25,7 +25,7 @@ def load_rod_model(
25
25
 
26
26
  Args:
27
27
  model_description: The URDF/SDF file or ROD model to load.
28
- is_urdf: Whether the model description is a URDF file.
28
+ is_urdf: Whether to force parsing the model description as a URDF file.
29
29
  model_name: The name of the model to load from the resource.
30
30
 
31
31
  Returns:
@@ -33,7 +33,7 @@ class SDFData(NamedTuple):
33
33
 
34
34
 
35
35
  def extract_model_data(
36
- model_description: pathlib.Path | str | rod.Model,
36
+ model_description: pathlib.Path | str | rod.Model | rod.Sdf,
37
37
  model_name: str | None = None,
38
38
  is_urdf: bool | None = None,
39
39
  ) -> SDFData:
@@ -41,30 +41,37 @@ def extract_model_data(
41
41
  Extract data from an SDF/URDF resource useful to build a JaxSim model.
42
42
 
43
43
  Args:
44
- model_description: A path to an SDF/URDF file, a string containing its content,
45
- or a pre-parsed/pre-built rod model.
44
+ model_description:
45
+ A path to an SDF/URDF file, a string containing its content, or
46
+ a pre-parsed/pre-built rod model.
46
47
  model_name: The name of the model to extract from the SDF resource.
47
- is_urdf: Whether the SDF resource is a URDF file. Needed only if model_description
48
- is a URDF string.
48
+ is_urdf:
49
+ Whether to force parsing the resource as a URDF file. Automatically
50
+ detected if not provided.
49
51
 
50
52
  Returns:
51
53
  The extracted model data.
52
54
  """
53
55
 
54
- if isinstance(model_description, rod.Model):
55
- sdf_model = model_description
56
- else:
57
- # Parse the SDF resource.
58
- sdf_element = rod.Sdf.load(sdf=model_description, is_urdf=is_urdf)
59
-
60
- if len(sdf_element.models()) == 0:
61
- raise RuntimeError("Failed to find any model in SDF resource")
62
-
63
- # Assume the SDF resource has only one model, or the desired model name is given.
64
- sdf_models = {m.name: m for m in sdf_element.models()}
65
- sdf_model = (
66
- sdf_element.models()[0] if len(sdf_models) == 1 else sdf_models[model_name]
67
- )
56
+ match model_description:
57
+ case rod.Model():
58
+ sdf_model = model_description
59
+ case rod.Sdf() | str() | pathlib.Path():
60
+ sdf_element = (
61
+ model_description
62
+ if isinstance(model_description, rod.Sdf)
63
+ else rod.Sdf.load(sdf=model_description, is_urdf=is_urdf)
64
+ )
65
+ if not sdf_element.models():
66
+ raise RuntimeError("Failed to find any model in SDF resource")
67
+
68
+ # Assume the SDF resource has only one model, or the desired model name is given.
69
+ sdf_models = {m.name: m for m in sdf_element.models()}
70
+ sdf_model = (
71
+ sdf_element.models()[0]
72
+ if len(sdf_models) == 1
73
+ else sdf_models[model_name]
74
+ )
68
75
 
69
76
  # Log model name.
70
77
  logging.debug(msg=f"Found model '{sdf_model.name}' in SDF resource")
@@ -344,7 +351,7 @@ def extract_model_data(
344
351
 
345
352
  def build_model_description(
346
353
  model_description: pathlib.Path | str | rod.Model,
347
- is_urdf: bool | None = False,
354
+ is_urdf: bool | None = None,
348
355
  ) -> descriptions.ModelDescription:
349
356
  """
350
357
  Builds a model description from an SDF/URDF resource.
@@ -352,8 +359,9 @@ def build_model_description(
352
359
  Args:
353
360
  model_description: A path to an SDF/URDF file, a string containing its content,
354
361
  or a pre-parsed/pre-built rod model.
355
- is_urdf: Whether the SDF resource is a URDF file. Needed only if model_description
356
- is a URDF string.
362
+ is_urdf: Whether the force parsing the resource as a URDF file. Automatically
363
+ detected if not provided.
364
+
357
365
  Returns:
358
366
  The parsed model description.
359
367
  """
@@ -215,6 +215,7 @@ class RigidContacts(ContactModel):
215
215
  link_forces: jtp.MatrixLike | None = None,
216
216
  joint_force_references: jtp.VectorLike | None = None,
217
217
  regularization_term: jtp.FloatLike = 1e-6,
218
+ solver_tol: jtp.FloatLike = 1e-3,
218
219
  ) -> tuple[jtp.Vector, tuple[Any, ...]]:
219
220
  """
220
221
  Compute the contact forces.
@@ -257,6 +258,9 @@ class RigidContacts(ContactModel):
257
258
  M = js.model.free_floating_mass_matrix(model=model, data=data)
258
259
  J_WC = js.contact.jacobian(model=model, data=data)
259
260
  W_H_C = js.contact.transforms(model=model, data=data)
261
+ J̇_WC_BW = js.contact.jacobian_derivative(model=model, data=data)
262
+ BW_ν = data.generalized_velocity()
263
+
260
264
  terrain_height = jax.vmap(self.terrain.height)(position[:, 0], position[:, 1])
261
265
  n_collidable_points = model.kin_dyn_parameters.contact_parameters.point.shape[0]
262
266
 
@@ -295,9 +299,10 @@ class RigidContacts(ContactModel):
295
299
  )
296
300
 
297
301
  free_contact_acc = RigidContacts._linear_acceleration_of_collidable_points(
298
- model,
299
- data,
300
- BW_ν̇_free,
302
+ BW_nu=BW_ν,
303
+ BW_nu_dot=BW_ν̇_free,
304
+ CW_J_WC_BW=J_WC,
305
+ CW_J_dot_WC_BW=J̇_WC_BW,
301
306
  ).flatten()
302
307
 
303
308
  # Compute stabilization term
@@ -325,7 +330,9 @@ class RigidContacts(ContactModel):
325
330
  b = jnp.zeros((0,))
326
331
 
327
332
  # Solve the optimization problem
328
- solution, *_ = qpax.solve_qp(Q=Q, q=q, A=A, b=b, G=G, h=h_bounds)
333
+ solution, *_ = qpax.solve_qp(
334
+ Q=Q, q=q, A=A, b=b, G=G, h=h_bounds, solver_tol=solver_tol
335
+ )
329
336
 
330
337
  f_C_lin = solution.reshape(-1, 3)
331
338
 
@@ -399,24 +406,14 @@ class RigidContacts(ContactModel):
399
406
 
400
407
  @staticmethod
401
408
  def _linear_acceleration_of_collidable_points(
402
- model: js.model.JaxSimModel,
403
- data: js.data.JaxSimModelData,
404
- mixed_nu_dot: jtp.ArrayLike,
409
+ BW_nu: jtp.ArrayLike,
410
+ BW_nu_dot: jtp.ArrayLike,
411
+ CW_J_WC_BW: jtp.MatrixLike,
412
+ CW_J_dot_WC_BW: jtp.MatrixLike,
405
413
  ) -> jtp.Matrix:
406
- with data.switch_velocity_representation(VelRepr.Mixed):
407
- CW_J_WC_BW = js.contact.jacobian(
408
- model=model,
409
- data=data,
410
- output_vel_repr=VelRepr.Mixed,
411
- )
412
- CW_J̇_WC_BW = js.contact.jacobian_derivative(
413
- model=model,
414
- data=data,
415
- output_vel_repr=VelRepr.Mixed,
416
- )
417
-
418
- BW_ν = data.generalized_velocity()
419
- BW_ν̇ = mixed_nu_dot
414
+ CW_J̇_WC_BW = CW_J_dot_WC_BW
415
+ BW_ν = BW_nu
416
+ BW_ν̇ = BW_nu_dot
420
417
 
421
418
  CW_a_WC = jnp.vstack(CW_J̇_WC_BW) @ BW_ν + jnp.vstack(CW_J_WC_BW) @ BW_ν̇
422
419
  CW_a_WC = CW_a_WC.reshape(-1, 6)
@@ -1,6 +1,6 @@
1
1
  Metadata-Version: 2.1
2
2
  Name: jaxsim
3
- Version: 0.4.3.dev97
3
+ Version: 0.4.3.dev105
4
4
  Summary: A differentiable physics engine and multibody dynamics library for control and robot learning.
5
5
  Author-email: Diego Ferigo <dgferigo@gmail.com>
6
6
  Maintainer-email: Diego Ferigo <dgferigo@gmail.com>, Filippo Luca Ferretti <filippo.ferretti@iit.it>
@@ -67,7 +67,7 @@ Requires-Dist: jaxlie>=1.3.0
67
67
  Requires-Dist: jax-dataclasses>=1.4.0
68
68
  Requires-Dist: pptree
69
69
  Requires-Dist: qpax
70
- Requires-Dist: rod>=0.3.0
70
+ Requires-Dist: rod>=0.3.3
71
71
  Requires-Dist: typing-extensions; python_version < "3.12"
72
72
  Provides-Extra: all
73
73
  Requires-Dist: jaxsim[style,testing,viz]; extra == "all"
@@ -1,18 +1,18 @@
1
1
  jaxsim/__init__.py,sha256=bSbpggIz5aG6QuGZLa0V2EfHjAOeucMxi-vIYxzLmN8,2788
2
- jaxsim/_version.py,sha256=riqB2Q7Zs4o0SGcY3Iy0aOEgFrNB6sdtU1rQ9czad4I,426
2
+ jaxsim/_version.py,sha256=1Pw2WIpSfIcMXUmFaqKP5hkuhIK6fZ2PSjrJqsDco98,428
3
3
  jaxsim/exceptions.py,sha256=8_h8iqL8DgNR754dR8SZiQ7361GR5V1sUk3ZuZCHw1Q,2069
4
4
  jaxsim/logging.py,sha256=STI-D_upXZYX-ZezLrlJJ0UlD5YspST0vZ_DcIwkzO4,1553
5
5
  jaxsim/typing.py,sha256=2HXy9hgazPXjofi1vLQ09ZubPtgVmg80U9NKmZ6NYiI,761
6
6
  jaxsim/api/__init__.py,sha256=8eV22t2S3UwNyCg8karPetG1dmX1VDBXkyv28_FwNQA,210
7
7
  jaxsim/api/com.py,sha256=m-p3EJDhpnMTlXKplfbZE_aH9NqX_VyLlAE3vUhc6l4,13642
8
8
  jaxsim/api/common.py,sha256=SNgxq42r6eF_-aPszvOjUYkGwXOzz4hKmhDwEUkscFQ,6650
9
- jaxsim/api/contact.py,sha256=lTCCYEh0t1XPz-hFapHzyU6c1LcCq6QcZgZnv3grXYE,22980
9
+ jaxsim/api/contact.py,sha256=BQMIMHBFYiHe_LVx_bwxKCpy20uiy0V-NljHfYXWhI0,23013
10
10
  jaxsim/api/data.py,sha256=QldUHniJqKrdNtAcXuRaS9UyeslJ0Rjvb17UA0Ca5Tw,29008
11
11
  jaxsim/api/frame.py,sha256=KS8A5wRfjxhe9NgcVo2QA516iP5zky7UVnWxG7nTa7c,12911
12
12
  jaxsim/api/joint.py,sha256=lksT1Doxz2jknHyhb4ls20z6f6dofpZSzBJtVacZXAE,7129
13
13
  jaxsim/api/kin_dyn_parameters.py,sha256=ElahFk_RCcLvjTidH2qDOsY-m1gN1hXitCv4SvfgGYY,29260
14
14
  jaxsim/api/link.py,sha256=LAA6ZMQXkWomXeptURBtc7z3_xDZ2BBnBMhVrohh0bE,18621
15
- jaxsim/api/model.py,sha256=CAxGDjSSP5coKQXM53pejnF1UmSo851UwZ3fz7JN8RE,67658
15
+ jaxsim/api/model.py,sha256=FLCk3fKUfLp3eCPrFEgPljTDp3zgIJnVW5Gwx0fWAog,67637
16
16
  jaxsim/api/ode.py,sha256=gYSbtHWGCDP-IkUzQlH3t0fBKnK8qmxwhIvsbLG9lwU,13616
17
17
  jaxsim/api/ode_data.py,sha256=7RSoBhfCJdP6P9InQbDwdBVpClPMMuetewI-6AWm-_0,20276
18
18
  jaxsim/api/references.py,sha256=XOVKuQXRmjPoP-T5JWGSbqIGX5DzOkeGafqRpj0ZQEM,20771
@@ -31,7 +31,7 @@ jaxsim/math/skew.py,sha256=oOGSSR8PUGROl6IJFlrmu6K3gPH-u16hUPfKIkcVv9o,1177
31
31
  jaxsim/math/transform.py,sha256=KXzQgOnCfAtbXCwxhplpJ3F0JT3oEyeLVby1_uRAryQ,2892
32
32
  jaxsim/mujoco/__init__.py,sha256=Zo5GAlN1DYKvX8s1hu1j6HntKIbBMLB9Puv9ouaNAZ8,158
33
33
  jaxsim/mujoco/__main__.py,sha256=GBmB7J-zj75ZnFyuAAmpSOpbxi_HhHhWJeot3ljGDJY,5291
34
- jaxsim/mujoco/loaders.py,sha256=_8Af_5Yo0-lWHE-46BBMcrqSJnDNxr3peyc519DExtA,25322
34
+ jaxsim/mujoco/loaders.py,sha256=qT7Le_L7z2prXKA7O9x5rkbbh-_lIrrmLXTjgoAjhZ4,25339
35
35
  jaxsim/mujoco/model.py,sha256=AQksXemXWACJ3yvefV2G5HLwwBU9ISoJrOD1wlxdY5w,16386
36
36
  jaxsim/mujoco/visualizer.py,sha256=T1vU-w4NKSmgEkZ0FqVcGmIvYrYO0len2UBSsU4MOZ0,6978
37
37
  jaxsim/parsers/__init__.py,sha256=47DEQpj8HBSa-_TImW-5JCeuQeRkm5NMpJWZG3hSuFU,0
@@ -42,7 +42,7 @@ jaxsim/parsers/descriptions/joint.py,sha256=VSb6C0FBBKMqwrHBKfc-Bbn4rl_J0RzUxMQl
42
42
  jaxsim/parsers/descriptions/link.py,sha256=Eh0W5qL7_Uw0GV-BkNKXhm9Q2dRTfIWCX5D-87zQkxA,3711
43
43
  jaxsim/parsers/descriptions/model.py,sha256=I2Vsbv8Josl4Le7b5rIvhqA2k9Bbv5JxMqwytayxds0,9833
44
44
  jaxsim/parsers/rod/__init__.py,sha256=G2vqlLajBLUc4gyzXwsEI2Wsi4TMOIF9bLDFeT6KrGU,92
45
- jaxsim/parsers/rod/parser.py,sha256=9EigYv2oGn4bfIY1q0Cd_55yVKfN2rXP_MuZSZqGxYM,13681
45
+ jaxsim/parsers/rod/parser.py,sha256=9zBYTQF2vC4NO6HEZBvV8VTaGuZSdbd3v66BAcMpuVI,13923
46
46
  jaxsim/parsers/rod/utils.py,sha256=5DsF3OeePZGidOJ5GiFSZx-51uIdnFvMW9EK6SgOW6Q,5698
47
47
  jaxsim/rbda/__init__.py,sha256=H7DhXpxkPOi9lpUvg31IMHFfRafke1UoJLc5GQIdyhA,387
48
48
  jaxsim/rbda/aba.py,sha256=w7ciyxB0IsmueatT0C7PcBQEl9dyiH9oqJgIi3xeTUE,8983
@@ -55,7 +55,7 @@ jaxsim/rbda/utils.py,sha256=eeT21Y4DiiyhrdF0lUE_VvRuwru5-rR7yOlOlWzCCWE,5381
55
55
  jaxsim/rbda/contacts/__init__.py,sha256=47DEQpj8HBSa-_TImW-5JCeuQeRkm5NMpJWZG3hSuFU,0
56
56
  jaxsim/rbda/contacts/common.py,sha256=VwAs742futAmLnDgbaOuLzNDBFiKDfYItdEZ4UcFgzE,2467
57
57
  jaxsim/rbda/contacts/relaxed_rigid.py,sha256=deTC0M2a_RER7iwVpxLCfuSlgBLqkTmHQdOJ4169IR4,13646
58
- jaxsim/rbda/contacts/rigid.py,sha256=zbSM0miwpgC1rp1d0RoQ1q8pYiKdIkHV8iZimeEPC94,15153
58
+ jaxsim/rbda/contacts/rigid.py,sha256=BYvQgoaG5yKo2N1SLlXgjP6cb1OrJ1BawGXkJf0Hhi0,15060
59
59
  jaxsim/rbda/contacts/soft.py,sha256=_wvb5iZDjGcVg6rNQelN4LZN7qSC2NIp0HdKvZmlGfk,15647
60
60
  jaxsim/terrain/__init__.py,sha256=f7lVX-iNpH_wkkjef9Qpjh19TTAUOQw76EiLYJDVizc,78
61
61
  jaxsim/terrain/terrain.py,sha256=xUQg47yGxIOcTkLPbnO3sruEGBhoCd16j1evTGlmNjI,5010
@@ -63,8 +63,8 @@ jaxsim/utils/__init__.py,sha256=Y5zyoRevl3EMVQadhZ4EtSwTEkDt2vcnFoRhPJjKTZ0,215
63
63
  jaxsim/utils/jaxsim_dataclass.py,sha256=TGmTQV2Lq7Q-2nLoAEaeNtkPa_qj0IKkdBm4COj46Os,11312
64
64
  jaxsim/utils/tracing.py,sha256=KDMoyVPlu2NJvFkhtZwq5AkqMMgajt3munvJom-vEjQ,650
65
65
  jaxsim/utils/wrappers.py,sha256=Fh82ZcaFi5fUnByyFLnmumaobsu1hJIvFdopUVzJ1ps,4052
66
- jaxsim-0.4.3.dev97.dist-info/LICENSE,sha256=eaYdFmdeMbiIoIiPzEK0MjP1S9wtFXjXNR5er49uLR0,1546
67
- jaxsim-0.4.3.dev97.dist-info/METADATA,sha256=53FEV8OdSD0cdz2Hm1dtfd_aPsJPrKoNkA4mycVTOco,17276
68
- jaxsim-0.4.3.dev97.dist-info/WHEEL,sha256=GV9aMThwP_4oNCtvEC2ec3qUYutgWeAzklro_0m4WJQ,91
69
- jaxsim-0.4.3.dev97.dist-info/top_level.txt,sha256=LxGMA8FLtXjQ6oI7N5gd_R_oSUHxpXxUEOfT1xS_ni0,7
70
- jaxsim-0.4.3.dev97.dist-info/RECORD,,
66
+ jaxsim-0.4.3.dev105.dist-info/LICENSE,sha256=eaYdFmdeMbiIoIiPzEK0MjP1S9wtFXjXNR5er49uLR0,1546
67
+ jaxsim-0.4.3.dev105.dist-info/METADATA,sha256=jYNJIkcAgei9qg7OLD7-E0HHYZRb3h4qFdmaVnyHXGo,17277
68
+ jaxsim-0.4.3.dev105.dist-info/WHEEL,sha256=GV9aMThwP_4oNCtvEC2ec3qUYutgWeAzklro_0m4WJQ,91
69
+ jaxsim-0.4.3.dev105.dist-info/top_level.txt,sha256=LxGMA8FLtXjQ6oI7N5gd_R_oSUHxpXxUEOfT1xS_ni0,7
70
+ jaxsim-0.4.3.dev105.dist-info/RECORD,,