jaxsim 0.5.1.dev86__py3-none-any.whl → 0.5.1.dev95__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.5.1.dev86'
16
- __version_tuple__ = version_tuple = (0, 5, 1, 'dev86')
15
+ __version__ = version = '0.5.1.dev95'
16
+ __version_tuple__ = version_tuple = (0, 5, 1, 'dev95')
jaxsim/api/data.py CHANGED
@@ -382,9 +382,8 @@ class JaxSimModelData(common.ModelDataWithVelocityRepresentation):
382
382
  # we introduce a Baumgarte stabilization to let the quaternion converge to
383
383
  # a unit quaternion. In this case, it is not guaranteed that the quaternion
384
384
  # stored in the state is a unit quaternion.
385
- W_Q_B = jnp.where(
386
- jnp.allclose(W_Q_B.dot(W_Q_B), 1.0), W_Q_B, W_Q_B / jnp.linalg.norm(W_Q_B)
387
- )
385
+ norm = jaxsim.math.safe_norm(W_Q_B)
386
+ W_Q_B = W_Q_B / (norm + jnp.finfo(float).eps * (norm == 0))
388
387
 
389
388
  return (W_Q_B if not dcm else jaxsim.math.Quaternion.to_dcm(W_Q_B)).astype(
390
389
  float
@@ -611,11 +610,8 @@ class JaxSimModelData(common.ModelDataWithVelocityRepresentation):
611
610
 
612
611
  W_Q_B = jnp.array(base_quaternion, dtype=float)
613
612
 
614
- W_Q_B = jax.lax.select(
615
- pred=jnp.allclose(jnp.linalg.norm(W_Q_B), 1.0, atol=1e-6, rtol=0.0),
616
- on_true=W_Q_B,
617
- on_false=W_Q_B / jnp.linalg.norm(W_Q_B),
618
- )
613
+ norm = jaxsim.math.safe_norm(W_Q_B)
614
+ W_Q_B = W_Q_B / (norm + jnp.finfo(float).eps * (norm == 0))
619
615
 
620
616
  return self.replace(
621
617
  validate=True,
@@ -53,10 +53,6 @@ class Integrator(JaxsimDataclass, abc.ABC, Generic[State, StateDerivative]):
53
53
  repr=False, hash=False, compare=False, kw_only=True
54
54
  )
55
55
 
56
- metadata: dict[str, Any] = dataclasses.field(
57
- default_factory=dict, repr=False, hash=False, compare=False, kw_only=True
58
- )
59
-
60
56
  @classmethod
61
57
  def build(
62
58
  cls: type[Self],
@@ -102,10 +98,7 @@ class Integrator(JaxsimDataclass, abc.ABC, Generic[State, StateDerivative]):
102
98
 
103
99
  metadata = metadata if metadata is not None else {}
104
100
 
105
- with self.editable(validate=False) as integrator:
106
- integrator.metadata = metadata
107
-
108
- with integrator.mutable_context(mutability=Mutability.MUTABLE):
101
+ with self.mutable_context(mutability=Mutability.MUTABLE) as integrator:
109
102
  xf, metadata_step = integrator(x0, t0, dt, **kwargs)
110
103
 
111
104
  return (
@@ -315,6 +308,9 @@ class ExplicitRungeKutta(Integrator[PyTreeType, PyTreeType], Generic[PyTreeType]
315
308
  b = self.b
316
309
  A = self.A
317
310
 
311
+ # Extract metadata from the kwargs.
312
+ metadata = kwargs.pop("metadata", {})
313
+
318
314
  # Close f over optional kwargs.
319
315
  f = lambda x, t: self.dynamics(x=x, t=t, **kwargs)
320
316
 
@@ -327,7 +323,7 @@ class ExplicitRungeKutta(Integrator[PyTreeType, PyTreeType], Generic[PyTreeType]
327
323
  # or to use the previous state derivative (only integrators supporting FSAL).
328
324
  def get_ẋ0_and_aux_dict() -> tuple[StateDerivative, dict[str, Any]]:
329
325
  ẋ0, aux_dict = f(x0, t0)
330
- return self.metadata.get("dxdt0", ẋ0), aux_dict
326
+ return metadata.get("dxdt0", ẋ0), aux_dict
331
327
 
332
328
  # We use a `jax.lax.scan` to compile the `f` function only once.
333
329
  # Otherwise, if we compute e.g. for RK4 sequentially, the jit-compiled code
@@ -381,7 +377,8 @@ class ExplicitRungeKutta(Integrator[PyTreeType, PyTreeType], Generic[PyTreeType]
381
377
 
382
378
  # Update the FSAL property for the next iteration.
383
379
  if self.has_fsal:
384
- self.metadata["dxdt0"] = jax.tree.map(lambda l: l[self.index_of_fsal], K)
380
+ # Store the first derivative of the next step in the metadata.
381
+ metadata["dxdt0"] = jax.tree.map(lambda l: l[self.index_of_fsal], K)
385
382
 
386
383
  # Compute the output state.
387
384
  # Note that z contains as many new states as the rows of `b.T`.
@@ -394,7 +391,7 @@ class ExplicitRungeKutta(Integrator[PyTreeType, PyTreeType], Generic[PyTreeType]
394
391
  lambda xf: self.post_process_state(x0=x0, t0=t0, xf=xf, dt=dt)
395
392
  )(z)
396
393
 
397
- return z_transformed, aux_dict
394
+ return z_transformed, aux_dict | {"metadata": metadata}
398
395
 
399
396
  @staticmethod
400
397
  def butcher_tableau_is_valid(
@@ -14,7 +14,6 @@ from jax_dataclasses import Static
14
14
 
15
15
  import jaxsim.utils.tracing
16
16
  from jaxsim import typing as jtp
17
- from jaxsim.utils import Mutability
18
17
 
19
18
  from .common import (
20
19
  ExplicitRungeKutta,
@@ -271,30 +270,27 @@ class EmbeddedRungeKutta(ExplicitRungeKutta[PyTreeType], Generic[PyTreeType]):
271
270
  # Inject this key to signal that the integrator is initializing.
272
271
  # This is used to allocate the arrays of the metadata dictionary,
273
272
  # that are then filled with NaNs.
274
- integrator.metadata = {EmbeddedRungeKutta.InitializingKey: jnp.array(True)}
273
+ metadata = {EmbeddedRungeKutta.InitializingKey: jnp.array(True)}
275
274
 
276
275
  # Run a dummy call of the integrator.
277
276
  # It is used only to get the metadata so that we know the structure
278
277
  # of the corresponding pytree.
279
278
  _ = integrator(
280
- x0, jnp.array(t0, dtype=float), jnp.array(dt, dtype=float), **kwargs
279
+ x0,
280
+ jnp.array(t0, dtype=float),
281
+ jnp.array(dt, dtype=float),
282
+ **(kwargs | {"metadata": metadata}),
281
283
  )
282
284
 
283
285
  # Remove the injected key.
284
- _ = integrator.metadata.pop(EmbeddedRungeKutta.InitializingKey)
286
+ _ = metadata.pop(EmbeddedRungeKutta.InitializingKey)
285
287
 
286
288
  # Make sure that all leafs of the dictionary are JAX arrays.
287
289
  # Also, since these are dummy parameters, set them all to NaN.
288
290
  metadata_after_init = jax.tree.map(
289
- lambda l: jnp.nan * jnp.zeros_like(l), integrator.metadata
291
+ lambda l: jnp.nan * jnp.zeros_like(l), metadata
290
292
  )
291
293
 
292
- # Store the zero parameters in the integrator.
293
- # When the integrator is stepped, this is used to check if the passed
294
- # parameters are valid.
295
- with self.mutable_context(mutability=Mutability.MUTABLE_NO_VALIDATION):
296
- self.metadata = metadata_after_init
297
-
298
294
  return metadata_after_init
299
295
 
300
296
  def __call__(
@@ -307,7 +303,7 @@ class EmbeddedRungeKutta(ExplicitRungeKutta[PyTreeType], Generic[PyTreeType]):
307
303
  # The metadata is a dictionary of float JAX arrays, that are initialized
308
304
  # with the right shape and filled with NaNs.
309
305
  # 2. During the first step, this method operates on the Nan-filled
310
- # `self.metadata` attribute, and it populates with the actual metadata.
306
+ # `metadata` argument, and it populates with the actual metadata.
311
307
  # 3. After the first step, this method operates on the actual metadata.
312
308
  #
313
309
  # In particular, we store the following information in the metadata:
@@ -318,8 +314,10 @@ class EmbeddedRungeKutta(ExplicitRungeKutta[PyTreeType], Generic[PyTreeType]):
318
314
  # evaluate the dynamics at the final state of the previous step, that matches
319
315
  # the initial state of the current step.
320
316
  #
317
+ metadata = kwargs.pop("metadata", {})
318
+
321
319
  integrator_init = jnp.array(
322
- self.metadata.get(self.InitializingKey, False), dtype=bool
320
+ metadata.get(self.InitializingKey, False), dtype=bool
323
321
  )
324
322
 
325
323
  # Close f over optional kwargs.
@@ -335,24 +333,23 @@ class EmbeddedRungeKutta(ExplicitRungeKutta[PyTreeType], Generic[PyTreeType]):
335
333
 
336
334
  # The value of dt0 is NaN (or, at least, it should be) only after initialization
337
335
  # and before the first step.
338
- self.metadata["dt0"], self.metadata["dxdt0"] = jax.lax.cond(
339
- pred=("dt0" in self.metadata)
340
- & ~jnp.isnan(self.metadata.get("dt0", 0.0)).any(),
336
+ metadata["dt0"], metadata["dxdt0"] = jax.lax.cond(
337
+ pred=("dt0" in metadata) & ~jnp.isnan(metadata.get("dt0", 0.0)).any(),
341
338
  true_fun=lambda metadata: (
342
339
  metadata.get("dt0", jnp.array(0.0, dtype=float)),
343
- self.metadata.get("dxdt0", f(x0, t0)[0]),
340
+ metadata.get("dxdt0", f(x0, t0)[0]),
344
341
  ),
345
342
  false_fun=lambda aux: estimate_step_size(
346
343
  x0=x0, t0=t0, f=f, order=p, atol=self.atol, rtol=self.rtol
347
344
  ),
348
- operand=self.metadata,
345
+ operand=metadata,
349
346
  )
350
347
 
351
348
  # Clip the estimated initial step size to the given bounds, if necessary.
352
- self.metadata["dt0"] = jnp.clip(
353
- self.metadata["dt0"],
354
- jnp.minimum(self.dt_min, self.metadata["dt0"]),
355
- jnp.minimum(self.dt_max, self.metadata["dt0"]),
349
+ metadata["dt0"] = jnp.clip(
350
+ metadata["dt0"],
351
+ jnp.minimum(self.dt_min, metadata["dt0"]),
352
+ jnp.minimum(self.dt_max, metadata["dt0"]),
356
353
  )
357
354
 
358
355
  # =========================================================
@@ -364,7 +361,7 @@ class EmbeddedRungeKutta(ExplicitRungeKutta[PyTreeType], Generic[PyTreeType]):
364
361
  carry0: Carry = (
365
362
  x0,
366
363
  jnp.array(t0).astype(float),
367
- self.metadata,
364
+ metadata,
368
365
  jnp.array(0, dtype=int),
369
366
  jnp.array(False).astype(bool),
370
367
  )
@@ -392,9 +389,10 @@ class EmbeddedRungeKutta(ExplicitRungeKutta[PyTreeType], Generic[PyTreeType]):
392
389
  # Run the underlying explicit RK integrator.
393
390
  # The output z contains multiple solutions (depending on the rows of b.T).
394
391
  with self.editable(validate=True) as integrator:
395
- integrator.metadata = metadata
396
- z, _ = integrator._compute_next_state(x0=x0, t0=t0, dt=Δt0, **kwargs)
397
- metadata_next = integrator.metadata
392
+ z, aux_dict = integrator._compute_next_state(
393
+ x0=x0, t0=t0, dt=Δt0, **kwargs
394
+ )
395
+ metadata_next = aux_dict["metadata"]
398
396
 
399
397
  # Extract the high-order solution xf and the low-order estimate x̂f.
400
398
  xf = jax.tree.map(lambda l: l[self.row_index_of_solution], z)
@@ -481,10 +479,10 @@ class EmbeddedRungeKutta(ExplicitRungeKutta[PyTreeType], Generic[PyTreeType]):
481
479
  metadata_next,
482
480
  discarded_steps,
483
481
  ) = jax.lax.cond(
484
- pred=discarded_steps
485
- >= self.max_step_rejections | local_error
486
- <= 1.0 | Δt_next
487
- < self.dt_min | integrator_init,
482
+ pred=(discarded_steps >= self.max_step_rejections)
483
+ | (local_error <= 1.0)
484
+ | (Δt_next < self.dt_min)
485
+ | integrator_init,
488
486
  true_fun=accept_step,
489
487
  false_fun=reject_step,
490
488
  )
@@ -510,12 +508,7 @@ class EmbeddedRungeKutta(ExplicitRungeKutta[PyTreeType], Generic[PyTreeType]):
510
508
  init_val=carry0,
511
509
  )
512
510
 
513
- # Store the parameters.
514
- # They will be returned to the caller in a functional way in the step method.
515
- with self.mutable_context(mutability=Mutability.MUTABLE):
516
- self.metadata = metadata_tf
517
-
518
- return xf, {}
511
+ return xf, {"metadata": metadata_tf}
519
512
 
520
513
  @property
521
514
  def order_of_solution(self) -> int:
jaxsim/math/__init__.py CHANGED
@@ -8,5 +8,6 @@ from .quaternion import Quaternion
8
8
  from .rotation import Rotation
9
9
  from .skew import Skew
10
10
  from .transform import Transform
11
+ from .utils import safe_norm
11
12
 
12
13
  from .joint_model import JointModel, supported_joint_motion # isort:skip
jaxsim/math/quaternion.py CHANGED
@@ -4,6 +4,8 @@ import jaxlie
4
4
 
5
5
  import jaxsim.typing as jtp
6
6
 
7
+ from .utils import safe_norm
8
+
7
9
 
8
10
  class Quaternion:
9
11
  @staticmethod
@@ -111,18 +113,13 @@ class Quaternion:
111
113
  operand=quaternion,
112
114
  )
113
115
 
114
- norm_ω = jax.lax.cond(
115
- pred=ω.dot(ω) < (1e-6) ** 2,
116
- true_fun=lambda _: 1e-6,
117
- false_fun=lambda _: jnp.linalg.norm(ω),
118
- operand=None,
119
- )
116
+ norm_ω = safe_norm(ω)
120
117
 
121
118
  qd = 0.5 * (
122
119
  Q
123
120
  @ jnp.hstack(
124
121
  [
125
- K * norm_ω * (1 - jnp.linalg.norm(quaternion)),
122
+ K * norm_ω * (1 - safe_norm(quaternion)),
126
123
  ω,
127
124
  ]
128
125
  )
jaxsim/math/rotation.py CHANGED
@@ -4,6 +4,7 @@ import jaxlie
4
4
  import jaxsim.typing as jtp
5
5
 
6
6
  from .skew import Skew
7
+ from .utils import safe_norm
7
8
 
8
9
 
9
10
  class Rotation:
@@ -67,7 +68,7 @@ class Rotation:
67
68
  def theta_is_not_zero(axis: jtp.Vector) -> jtp.Matrix:
68
69
 
69
70
  v = axis
70
- theta = jnp.linalg.norm(v)
71
+ theta = safe_norm(v)
71
72
 
72
73
  s = jnp.sin(theta)
73
74
  c = jnp.cos(theta)
@@ -81,19 +82,9 @@ class Rotation:
81
82
 
82
83
  return R.transpose()
83
84
 
84
- # Use the double-where trick to prevent JAX problems when the
85
- # jax.jit and jax.grad transforms are applied.
86
85
  return jnp.where(
87
- jnp.linalg.norm(vector) > 0,
88
- theta_is_not_zero(
89
- axis=jnp.where(
90
- jnp.linalg.norm(vector) > 0,
91
- vector,
92
- # The following line is a workaround to prevent division by 0.
93
- # Considering the outer where, this branch is never executed.
94
- jnp.ones(3),
95
- )
96
- ),
86
+ jnp.allclose(vector, 0.0),
97
87
  # Return an identity rotation matrix when the input vector is zero.
98
88
  jnp.eye(3),
89
+ theta_is_not_zero(axis=vector),
99
90
  )
jaxsim/math/utils.py ADDED
@@ -0,0 +1,31 @@
1
+ import jax.numpy as jnp
2
+
3
+ import jaxsim.typing as jtp
4
+
5
+
6
+ def safe_norm(array: jtp.ArrayLike, axis=None) -> jtp.Array:
7
+ """
8
+ Provides a calculation for an array norm so that it is safe
9
+ to compute the gradient and handle NaNs.
10
+
11
+ Args:
12
+ array: The array for which to compute the norm.
13
+ axis: The axis for which to compute the norm.
14
+
15
+ Returns:
16
+ The norm of the array with handling for zero arrays to avoid NaNs.
17
+ """
18
+
19
+ # Check if the entire array is composed of zeros.
20
+ is_zero = jnp.allclose(array, 0.0)
21
+
22
+ # Replace zeros with an array of ones temporarily to avoid division by zero.
23
+ # This ensures the computation of norm does not produce NaNs or Infs.
24
+ array = jnp.where(is_zero, jnp.ones_like(array), array)
25
+
26
+ # Compute the norm of the array along the specified axis.
27
+ norm = jnp.linalg.norm(array, axis=axis)
28
+
29
+ # Use `jnp.where` to set the norm to 0.0 where the input array was all zeros.
30
+ # This usage supports potential batch processing for future scalability.
31
+ return jnp.where(is_zero, 0.0, norm)
@@ -309,19 +309,16 @@ class SoftContacts(common.ContactModel):
309
309
 
310
310
  # Compute the direction of the tangential force.
311
311
  # To prevent dividing by zero, we use a switch statement.
312
- # The ε, instead, is needed to make AD happy.
313
- f_tangential_direction = jnp.where(
314
- f_tangential.dot(f_tangential) != 0,
315
- f_tangential / jnp.linalg.norm(f_tangential + ε),
316
- jnp.zeros(3),
312
+ norm = jaxsim.math.safe_norm(f_tangential)
313
+ f_tangential_direction = f_tangential / (
314
+ norm + jnp.finfo(float).eps * (norm == 0)
317
315
  )
318
316
 
319
317
  # Project the tangential force to the friction cone if slipping.
320
318
  f_tangential = jnp.where(
321
319
  sticking,
322
320
  f_tangential,
323
- jnp.minimum(μ * force_normal_mag, jnp.linalg.norm(f_tangential + ε))
324
- * f_tangential_direction,
321
+ jnp.minimum(μ * force_normal_mag, norm) * f_tangential_direction,
325
322
  )
326
323
 
327
324
  # Set the tangential force to zero if there is no contact.
jaxsim/terrain/terrain.py CHANGED
@@ -7,6 +7,7 @@ import jax.numpy as jnp
7
7
  import jax_dataclasses
8
8
  import numpy as np
9
9
 
10
+ import jaxsim.math
10
11
  import jaxsim.typing as jtp
11
12
  from jaxsim import exceptions
12
13
 
@@ -41,7 +42,7 @@ class Terrain(abc.ABC):
41
42
  [(h_xm - h_xp) / (2 * self.delta), (h_ym - h_yp) / (2 * self.delta), 1.0]
42
43
  )
43
44
 
44
- return n / jnp.linalg.norm(n)
45
+ return n / jaxsim.math.safe_norm(n)
45
46
 
46
47
 
47
48
  @jax_dataclasses.pytree_dataclass
@@ -1,6 +1,6 @@
1
1
  Metadata-Version: 2.1
2
2
  Name: jaxsim
3
- Version: 0.5.1.dev86
3
+ Version: 0.5.1.dev95
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>, Filippo Luca Ferretti <filippoluca.ferretti@outlook.com>
6
6
  Maintainer-email: Filippo Luca Ferretti <filippo.ferretti@iit.it>, Alessandro Croci <alessandro.croci@iit.it>
@@ -1,5 +1,5 @@
1
1
  jaxsim/__init__.py,sha256=opgtbhhd1kDsHI4H1vOd3loMPDRi884yQ3tohfFGfNc,3382
2
- jaxsim/_version.py,sha256=2nWfd54AgYYlO27pKe_wwyCtkKok4970qswX81HrrTc,426
2
+ jaxsim/_version.py,sha256=uLmioR8f_16hLO76GPSpzQyclhE2S-4nH8pntMObYGY,426
3
3
  jaxsim/exceptions.py,sha256=Sq3qtqeiy-CK76new_W2KKQ-4MAzyOUK5j5pBLr4RPQ,2250
4
4
  jaxsim/logging.py,sha256=STI-D_upXZYX-ZezLrlJJ0UlD5YspST0vZ_DcIwkzO4,1553
5
5
  jaxsim/typing.py,sha256=2HXy9hgazPXjofi1vLQ09ZubPtgVmg80U9NKmZ6NYiI,761
@@ -7,7 +7,7 @@ jaxsim/api/__init__.py,sha256=8eV22t2S3UwNyCg8karPetG1dmX1VDBXkyv28_FwNQA,210
7
7
  jaxsim/api/com.py,sha256=5fYNRUhKE5VGGdW88zY8mqqEy5VTWyaHu5k6MgW4Jt4,13826
8
8
  jaxsim/api/common.py,sha256=SvEOGxCKOxKLLVHaNp1sFkBX0sku3-wH0-HUlYVWCDk,7090
9
9
  jaxsim/api/contact.py,sha256=vfW-HEvQcAUHl7dOOwI-ndRxgMeAtkKT7tTaMDFlh7k,25421
10
- jaxsim/api/data.py,sha256=hz8g-P0o7XoDYyUFPx6yA8QlgHmjfFf2_OdiwcRV6W8,30292
10
+ jaxsim/api/data.py,sha256=AFp1sDNRIkwpBom6ZlW6L7vJBtf4D9woVRJ8bGICr3s,30189
11
11
  jaxsim/api/frame.py,sha256=d6pa6vywGDqfaJU76F_-yjLJs6R3mrjZ6B-KXPu6f3Q,14595
12
12
  jaxsim/api/joint.py,sha256=AnqlNWmBOay-gsoo0y4AbfFQ2OCJm-8T1E0IMhZeLoY,7457
13
13
  jaxsim/api/kin_dyn_parameters.py,sha256=wnto0nzzEJ_M8tH2PUdldEyxQwQdsStYUoQFu696uuw,29897
@@ -17,18 +17,19 @@ jaxsim/api/ode.py,sha256=SIg7UKDkJxhS0FlMH6iqipn7WoQWjpQP6EFdvEBkdts,15429
17
17
  jaxsim/api/ode_data.py,sha256=ggF1AVaLW5QuXrfpNsFs-voVcW6gZkxK2Xe9GiDmou0,13755
18
18
  jaxsim/api/references.py,sha256=YkdZhRv8NoBC94qvpwn1w9_alVuxrfiZV5w5NHQIt-g,20737
19
19
  jaxsim/integrators/__init__.py,sha256=hxvOD-VK_mmd6v31wtC-nb28AYve1gLuZCNLV9wS-Kg,103
20
- jaxsim/integrators/common.py,sha256=ohISUnUWTaNHt2kweg1JyzwYGZgIH_wc-01qJWJsO80,18281
20
+ jaxsim/integrators/common.py,sha256=fnDqVIIXMYe2aiT_qnEhJSAeFuYRGhmElVCl7zPTrN8,18229
21
21
  jaxsim/integrators/fixed_step.py,sha256=KpjRd6hHtapxDoo6D1kyDrVDSHnke2TepI5grFH7_bM,2693
22
- jaxsim/integrators/variable_step.py,sha256=Tqz5ySSgyKak_k6cTXpmtqdPNaFlO7N6zj7jBIlChyM,22681
23
- jaxsim/math/__init__.py,sha256=8oPITEoGwgRcOeG8KxtqxPQ8b5uku1HNRMokpCoi9Tc,352
22
+ jaxsim/integrators/variable_step.py,sha256=HuUKudeFj0W7dvVATVNZK3uk1Nh_qKlGO_CDqXJFV14,22166
23
+ jaxsim/math/__init__.py,sha256=2T1WUU_chNBCvyvkKSdiesPlckbo-gXVbCZEGoF-W0I,381
24
24
  jaxsim/math/adjoint.py,sha256=V7r5VrTCKPLEL5gavNSx9U7xSsrb11a5e4gWqJ2MuRo,4375
25
25
  jaxsim/math/cross.py,sha256=U7yEx_l75mSy5g6O-jsjBztApvxC3WaV4MpkS5tThu4,1330
26
26
  jaxsim/math/inertia.py,sha256=01hz6wMFreN2jBA0rVoBS1YMVh77KvwuzXSOpI3pxNk,1614
27
27
  jaxsim/math/joint_model.py,sha256=EzAveaG5B6ZnCFNUzN30KEQUVesd83lfWXJarYR-kUw,9989
28
- jaxsim/math/quaternion.py,sha256=_WA7W3iv7px83sWO1V1n0-J78hqAlO4SL1-jofE-UZ4,4754
29
- jaxsim/math/rotation.py,sha256=P34sx28Rh1MhNwxUxqXjxP-ZN1_5tvoflMoAIpy2LbE,2586
28
+ jaxsim/math/quaternion.py,sha256=vrPkdSUPfv1RZOULY9uG_bxmqgOARdvMxKtb6QixHuY,4609
29
+ jaxsim/math/rotation.py,sha256=W6vaIWmoBBuPgNJKey1vFpl2a1IxXTToCTaPfs-kd9I,2155
30
30
  jaxsim/math/skew.py,sha256=oOGSSR8PUGROl6IJFlrmu6K3gPH-u16hUPfKIkcVv9o,1177
31
31
  jaxsim/math/transform.py,sha256=KXzQgOnCfAtbXCwxhplpJ3F0JT3oEyeLVby1_uRAryQ,2892
32
+ jaxsim/math/utils.py,sha256=C5kP11KWsIacWtzouaI5tNH8BHjZ-ZgZ67U9wzjz7jw,1070
32
33
  jaxsim/mujoco/__init__.py,sha256=fZyRWre49pIhOrYdf6yJk_hOax8qWGe8OCmoq-dMVq8,201
33
34
  jaxsim/mujoco/__main__.py,sha256=GBmB7J-zj75ZnFyuAAmpSOpbxi_HhHhWJeot3ljGDJY,5291
34
35
  jaxsim/mujoco/loaders.py,sha256=_CZekIqZNe8oFeH7zSv4gGZAZENRISwMd8dt640zjRI,20860
@@ -58,16 +59,16 @@ jaxsim/rbda/contacts/__init__.py,sha256=L5MM-2pv76YPGzxExdz2EErgGBATuAjYnNHlq5QO
58
59
  jaxsim/rbda/contacts/common.py,sha256=BjwZMCkzd1ZOdZW7_Zt09Cl5j2JUHXM5Q8ao_qS6e64,10406
59
60
  jaxsim/rbda/contacts/relaxed_rigid.py,sha256=PgwKfProN5sLXJsSov3nIidHHMVpJqIp7eIv6_bPGjs,20345
60
61
  jaxsim/rbda/contacts/rigid.py,sha256=X-PE6PmZqlKoZTY6JhYBSW-vom-rq2uBKmBUNQeQHCg,15991
61
- jaxsim/rbda/contacts/soft.py,sha256=sIWT4NUJmoVR5T1Fo0ExdPfzL_gPfiPiB-9CFuotE_s,15567
62
+ jaxsim/rbda/contacts/soft.py,sha256=MhqHThn3XVyy8lRg6QVYzcJF4vVRKwnMvOMEyyF96OE,15443
62
63
  jaxsim/rbda/contacts/visco_elastic.py,sha256=QhyJHjDowyBTAhoSdZcCIkOqzp__gMXhLON-qYyMgQc,39886
63
64
  jaxsim/terrain/__init__.py,sha256=f7lVX-iNpH_wkkjef9Qpjh19TTAUOQw76EiLYJDVizc,78
64
- jaxsim/terrain/terrain.py,sha256=_G1QS3zWycj089R8fTP5s2VjcZpEdJxREjXZJ-oXIvc,5248
65
+ jaxsim/terrain/terrain.py,sha256=bv-YAwG06EydHnB6bcNtl7xIyB3LSl0vVXSVLFC4JpQ,5273
65
66
  jaxsim/utils/__init__.py,sha256=Y5zyoRevl3EMVQadhZ4EtSwTEkDt2vcnFoRhPJjKTZ0,215
66
67
  jaxsim/utils/jaxsim_dataclass.py,sha256=TGmTQV2Lq7Q-2nLoAEaeNtkPa_qj0IKkdBm4COj46Os,11312
67
68
  jaxsim/utils/tracing.py,sha256=eEY28MZW0Lm_jJNt1NkFqZz0ek01tvhR46OXZYCo7tc,532
68
69
  jaxsim/utils/wrappers.py,sha256=ZY7olSORzZRvSzkdeNLj8yjwUIAt9L0Douwl7wItjpk,4008
69
- jaxsim-0.5.1.dev86.dist-info/LICENSE,sha256=eaYdFmdeMbiIoIiPzEK0MjP1S9wtFXjXNR5er49uLR0,1546
70
- jaxsim-0.5.1.dev86.dist-info/METADATA,sha256=GQtBCi6r0B5xji-AMKVBniNryixi5LbnvE4xvfJs45Q,17937
71
- jaxsim-0.5.1.dev86.dist-info/WHEEL,sha256=PZUExdf71Ui_so67QXpySuHtCi3-J3wvF4ORK6k_S8U,91
72
- jaxsim-0.5.1.dev86.dist-info/top_level.txt,sha256=LxGMA8FLtXjQ6oI7N5gd_R_oSUHxpXxUEOfT1xS_ni0,7
73
- jaxsim-0.5.1.dev86.dist-info/RECORD,,
70
+ jaxsim-0.5.1.dev95.dist-info/LICENSE,sha256=eaYdFmdeMbiIoIiPzEK0MjP1S9wtFXjXNR5er49uLR0,1546
71
+ jaxsim-0.5.1.dev95.dist-info/METADATA,sha256=xOMthPKBfJqlJrzyVADzPjB5b-h8MKI3K8CGRdcKZy4,17937
72
+ jaxsim-0.5.1.dev95.dist-info/WHEEL,sha256=A3WOREP4zgxI0fKrHUG8DC8013e3dK3n7a6HDbcEIwE,91
73
+ jaxsim-0.5.1.dev95.dist-info/top_level.txt,sha256=LxGMA8FLtXjQ6oI7N5gd_R_oSUHxpXxUEOfT1xS_ni0,7
74
+ jaxsim-0.5.1.dev95.dist-info/RECORD,,
@@ -1,5 +1,5 @@
1
1
  Wheel-Version: 1.0
2
- Generator: setuptools (75.6.0)
2
+ Generator: setuptools (75.7.0)
3
3
  Root-Is-Purelib: true
4
4
  Tag: py3-none-any
5
5