jaxsim 0.2.dev376__py3-none-any.whl → 0.2.dev394__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.2.dev376'
16
- __version_tuple__ = version_tuple = (0, 2, 'dev376')
15
+ __version__ = version = '0.2.dev394'
16
+ __version_tuple__ = version_tuple = (0, 2, 'dev394')
jaxsim/api/common.py CHANGED
@@ -89,7 +89,7 @@ class ModelDataWithVelocityRepresentation(JaxsimDataclass, abc.ABC):
89
89
  transform: jtp.Matrix,
90
90
  is_force: bool = False,
91
91
  ) -> jtp.Array:
92
- """
92
+ r"""
93
93
  Convert a 6D quantity from inertial-fixed to another representation.
94
94
 
95
95
  Args:
@@ -155,7 +155,7 @@ class ModelDataWithVelocityRepresentation(JaxsimDataclass, abc.ABC):
155
155
  transform: jtp.Matrix,
156
156
  is_force: bool = False,
157
157
  ) -> jtp.Array:
158
- """
158
+ r"""
159
159
  Convert a 6D quantity from another representation to inertial-fixed.
160
160
 
161
161
  Args:
jaxsim/api/data.py CHANGED
@@ -415,9 +415,9 @@ class JaxSimModelData(common.ModelDataWithVelocityRepresentation):
415
415
 
416
416
  @jax.jit
417
417
  def generalized_position(self) -> tuple[jtp.Matrix, jtp.Vector]:
418
- """
418
+ r"""
419
419
  Get the generalized position
420
- :math:`\mathbf{q} = ({}^W \mathbf{H}_B, \mathbf{s}) \in \text{SO}(3) \times \mathbb{R}^n`.
420
+ :math:`\\mathbf{q} = ({}^W \\mathbf{H}_B, \\mathbf{s}) \\in \text{SO}(3) \times \\mathbb{R}^n`.
421
421
 
422
422
  Returns:
423
423
  A tuple containing the base transform and the joint positions.
@@ -427,9 +427,9 @@ class JaxSimModelData(common.ModelDataWithVelocityRepresentation):
427
427
 
428
428
  @jax.jit
429
429
  def generalized_velocity(self) -> jtp.Vector:
430
- """
430
+ r"""
431
431
  Get the generalized velocity
432
- :math:`\boldsymbol{\nu} = (\boldsymbol{v}_{W,B};\, \boldsymbol{\omega}_{W,B};\, \mathbf{s}) \in \mathbb{R}^{6+n}`
432
+ :math:`\boldsymbol{\nu} = (\boldsymbol{v}_{W,B};\\, \boldsymbol{\\omega}_{W,B};\\, \\mathbf{s}) \\in \\mathbb{R}^{6+n}`
433
433
 
434
434
  Returns:
435
435
  The generalized velocity in the active representation.
jaxsim/api/link.py CHANGED
@@ -335,3 +335,27 @@ def velocity(
335
335
 
336
336
  # Compute the link velocity in the output velocity representation.
337
337
  return O_J_WL_I @ I_ν
338
+
339
+
340
+ @jax.jit
341
+ def bias_acceleration(
342
+ model: js.model.JaxSimModel,
343
+ data: js.data.JaxSimModelData,
344
+ *,
345
+ link_index: jtp.IntLike,
346
+ ) -> jtp.Vector:
347
+ """
348
+ Compute the bias acceleration of the link.
349
+
350
+ Args:
351
+ model: The model to consider.
352
+ data: The data of the considered model.
353
+ link_index: The index of the link.
354
+
355
+ Returns:
356
+ The 6D bias acceleration of the link.
357
+ """
358
+
359
+ # Compute the bias acceleration of all links in the active representation.
360
+ O_v̇_WL = js.model.link_bias_accelerations(model=model, data=data)[link_index]
361
+ return O_v̇_WL
jaxsim/api/model.py CHANGED
@@ -937,7 +937,7 @@ def inverse_dynamics(
937
937
  def free_floating_gravity_forces(
938
938
  model: JaxSimModel, data: js.data.JaxSimModelData
939
939
  ) -> jtp.Vector:
940
- """
940
+ r"""
941
941
  Compute the free-floating gravity forces :math:`g(\mathbf{q})` of the model.
942
942
 
943
943
  Args:
@@ -987,7 +987,7 @@ def free_floating_bias_forces(
987
987
  model: JaxSimModel, data: js.data.JaxSimModelData
988
988
  ) -> jtp.Vector:
989
989
  """
990
- Compute the free-floating bias forces :math:`h(\mathbf{q}, \boldsymbol{\nu})`
990
+ Compute the free-floating bias forces :math:`h(\\mathbf{q}, \boldsymbol{\nu})`
991
991
  of the model.
992
992
 
993
993
  Args:
@@ -1243,6 +1243,211 @@ def average_velocity_jacobian(
1243
1243
  # ========================
1244
1244
 
1245
1245
 
1246
+ @jax.jit
1247
+ def link_bias_accelerations(
1248
+ model: JaxSimModel,
1249
+ data: js.data.JaxSimModelData,
1250
+ ) -> jtp.Vector:
1251
+ r"""
1252
+ Compute the bias accelerations of the links of the model.
1253
+
1254
+ Args:
1255
+ model: The model to consider.
1256
+ data: The data of the considered model.
1257
+
1258
+ Returns:
1259
+ The bias accelerations of the links of the model.
1260
+
1261
+ Note:
1262
+ This function computes the component of the total 6D acceleration not due to
1263
+ the joint or base acceleration.
1264
+ It is often called :math:`\dot{J} \boldsymbol{\nu}`.
1265
+ """
1266
+
1267
+ # ================================================
1268
+ # Compute the body-fixed zero base 6D acceleration
1269
+ # ================================================
1270
+
1271
+ # Compute the base transform.
1272
+ W_H_B = jaxlie.SE3.from_rotation_and_translation(
1273
+ rotation=jaxlie.SO3.from_quaternion_xyzw(
1274
+ xyzw=jaxsim.math.Quaternion.to_xyzw(wxyz=data.base_orientation())
1275
+ ),
1276
+ translation=data.base_position(),
1277
+ ).as_matrix()
1278
+
1279
+ def other_representation_to_inertial(
1280
+ C_v̇_WB: jtp.Vector, C_v_WB: jtp.Vector, W_H_C: jtp.Matrix, W_v_WC: jtp.Vector
1281
+ ) -> jtp.Vector:
1282
+ """
1283
+ Helper to convert the active representation of the base acceleration C_v̇_WB
1284
+ expressed in a generic frame C to the inertial-fixed representation W_v̇_WB.
1285
+ """
1286
+
1287
+ W_X_C = jaxlie.SE3.from_matrix(W_H_C).adjoint()
1288
+ C_X_W = jaxlie.SE3.from_matrix(W_H_C).inverse().adjoint()
1289
+
1290
+ # In Mixed representation, we need to include a cross product in ℝ⁶.
1291
+ # In Inertial and Body representations, the cross product is always zero.
1292
+ return W_X_C @ (C_v̇_WB + jaxsim.math.Cross.vx(C_X_W @ W_v_WC) @ C_v_WB)
1293
+
1294
+ # Here we initialize a zero 6D acceleration in the active representation, and
1295
+ # convert it to inertial-fixed. This is a useful intermediate representation
1296
+ # because the apparent acceleration W_v̇_WB is equal to the intrinsic acceleration
1297
+ # W_a_WB, and intrinsic accelerations can be expressed in different frames through
1298
+ # a simple C_X_W 6D transform.
1299
+ match data.velocity_representation:
1300
+ case VelRepr.Inertial:
1301
+ W_H_C = W_H_W = jnp.eye(4)
1302
+ W_v_WC = W_v_WW = jnp.zeros(6)
1303
+ with data.switch_velocity_representation(VelRepr.Inertial):
1304
+ C_v_WB = W_v_WB = data.base_velocity()
1305
+
1306
+ case VelRepr.Body:
1307
+ W_H_C = W_H_B
1308
+ with data.switch_velocity_representation(VelRepr.Inertial):
1309
+ W_v_WC = W_v_WB = data.base_velocity()
1310
+ with data.switch_velocity_representation(VelRepr.Body):
1311
+ C_v_WB = B_v_WB = data.base_velocity()
1312
+
1313
+ case VelRepr.Mixed:
1314
+ W_H_BW = W_H_B.at[0:3, 0:3].set(jnp.eye(3))
1315
+ W_H_C = W_H_BW
1316
+ with data.switch_velocity_representation(VelRepr.Mixed):
1317
+ W_ṗ_B = data.base_velocity()[0:3]
1318
+ W_v_WC = W_v_W_BW = jnp.zeros(6).at[0:3].set(W_ṗ_B)
1319
+ with data.switch_velocity_representation(VelRepr.Mixed):
1320
+ C_v_WB = BW_v_WB = data.base_velocity()
1321
+ case _:
1322
+ raise ValueError(data.velocity_representation)
1323
+
1324
+ # Convert a zero 6D acceleration from the active representation to inertial-fixed.
1325
+ W_v̇_WB = other_representation_to_inertial(
1326
+ C_v̇_WB=jnp.zeros(6), C_v_WB=C_v_WB, W_H_C=W_H_C, W_v_WC=W_v_WC
1327
+ )
1328
+
1329
+ # ===================================
1330
+ # Initialize buffers and prepare data
1331
+ # ===================================
1332
+
1333
+ # Get the parent array λ(i).
1334
+ # Note: λ(0) must not be used, it's initialized to -1.
1335
+ λ = model.kin_dyn_parameters.parent_array
1336
+
1337
+ # Compute 6D transforms of the base velocity.
1338
+ B_X_W = jaxsim.math.Adjoint.from_transform(transform=W_H_B, inverse=True)
1339
+
1340
+ # Compute the parent-to-child adjoints and the motion subspaces of the joints.
1341
+ # These transforms define the relative kinematics of the entire model, including
1342
+ # the base transform for both floating-base and fixed-base models.
1343
+ i_X_λi, S = model.kin_dyn_parameters.joint_transforms_and_motion_subspaces(
1344
+ joint_positions=data.joint_positions(), base_transform=W_H_B
1345
+ )
1346
+
1347
+ # Allocate the buffer to store the body-fixed link velocities.
1348
+ L_v_WL = jnp.zeros(shape=(model.number_of_links(), 6))
1349
+
1350
+ # Store the base velocity.
1351
+ with data.switch_velocity_representation(VelRepr.Body):
1352
+ B_v_WB = data.base_velocity()
1353
+ L_v_WL = L_v_WL.at[0].set(B_v_WB)
1354
+
1355
+ # Get the joint velocities.
1356
+ ṡ = data.joint_velocities(model=model, joint_names=model.joint_names())
1357
+
1358
+ # Allocate the buffer to store the body-fixed link accelerations,
1359
+ # and initialize the base acceleration.
1360
+ L_v̇_WL = jnp.zeros(shape=(model.number_of_links(), 6))
1361
+ L_v̇_WL = L_v̇_WL.at[0].set(B_X_W @ W_v̇_WB)
1362
+
1363
+ # ======================================
1364
+ # Propagate accelerations and velocities
1365
+ # ======================================
1366
+
1367
+ # The computation of the bias forces is similar to the forward pass of RNEA,
1368
+ # this time with zero base and joint accelerations. Furthermore, here we do
1369
+ # not remove gravity during the propagation.
1370
+
1371
+ # Initialize the loop.
1372
+ Carry = tuple[jtp.MatrixJax, jtp.MatrixJax]
1373
+ carry0: Carry = (L_v_WL, L_v̇_WL)
1374
+
1375
+ def propagate_accelerations(carry: Carry, i: jtp.Int) -> tuple[Carry, None]:
1376
+ # Initialize index and unpack the carry.
1377
+ ii = i - 1
1378
+ v, a = carry
1379
+
1380
+ # Get the motion subspace of the joint.
1381
+ Si = S[i].squeeze()
1382
+
1383
+ # Project the joint velocity into its motion subspace.
1384
+ vJ = Si * ṡ[ii]
1385
+
1386
+ # Propagate the link body-fixed velocity.
1387
+ v_i = i_X_λi[i] @ v[λ[i]] + vJ
1388
+ v = v.at[i].set(v_i)
1389
+
1390
+ # Propagate the link body-fixed acceleration considering zero joint acceleration.
1391
+ s̈ = 0.0
1392
+ a_i = i_X_λi[i] @ a[λ[i]] + Si * s̈ + jaxsim.math.Cross.vx(v[i]) @ vJ
1393
+ a = a.at[i].set(a_i)
1394
+
1395
+ return (v, a), None
1396
+
1397
+ # Compute the body-fixed velocity and body-fixed apparent acceleration of the links.
1398
+ (L_v_WL, L_v̇_WL), _ = (
1399
+ jax.lax.scan(
1400
+ f=propagate_accelerations,
1401
+ init=carry0,
1402
+ xs=jnp.arange(start=1, stop=model.number_of_links()),
1403
+ )
1404
+ if model.number_of_links() > 1
1405
+ else [(L_v_WL, L_v̇_WL), None]
1406
+ )
1407
+
1408
+ # ===================================================================
1409
+ # Convert the body-fixed 6D acceleration to the active representation
1410
+ # ===================================================================
1411
+
1412
+ def body_to_other_representation(
1413
+ L_v̇_WL: jtp.Vector, L_v_WL: jtp.Vector, C_H_L: jtp.Matrix, L_v_CL: jtp.Vector
1414
+ ) -> jtp.Vector:
1415
+ """
1416
+ Helper to convert the body-fixed apparent acceleration L_v̇_WL to
1417
+ another representation C_v̇_WL expressed in a generic frame C.
1418
+ """
1419
+
1420
+ # In Mixed representation, we need to include a cross product in ℝ⁶.
1421
+ # In Inertial and Body representations, the cross product is always zero.
1422
+ C_X_L = jaxsim.math.Adjoint.from_transform(transform=C_H_L)
1423
+ return C_X_L @ (L_v̇_WL + jaxsim.math.Cross.vx(L_v_CL) @ L_v_WL)
1424
+
1425
+ match data.velocity_representation:
1426
+ case VelRepr.Body:
1427
+ C_H_L = L_H_L = jnp.stack([jnp.eye(4)] * model.number_of_links())
1428
+ L_v_CL = L_v_LL = jnp.zeros(shape=(model.number_of_links(), 6))
1429
+
1430
+ case VelRepr.Inertial:
1431
+ C_H_L = W_H_L = js.model.forward_kinematics(model=model, data=data)
1432
+ L_v_CL = L_v_WL
1433
+
1434
+ case VelRepr.Mixed:
1435
+ W_H_L = js.model.forward_kinematics(model=model, data=data)
1436
+ LW_H_L = jax.vmap(lambda W_H_L: W_H_L.at[0:3, 3].set(jnp.zeros(3)))(W_H_L)
1437
+ C_H_L = LW_H_L
1438
+ L_v_CL = L_v_LW_L = jax.vmap(lambda v: v.at[0:3].set(jnp.zeros(3)))(L_v_WL)
1439
+
1440
+ case _:
1441
+ raise ValueError(data.velocity_representation)
1442
+
1443
+ # Convert from body-fixed to the active representation.
1444
+ O_v̇_WL = jax.vmap(body_to_other_representation)(
1445
+ L_v̇_WL=L_v̇_WL, L_v_WL=L_v_WL, C_H_L=C_H_L, L_v_CL=L_v_CL
1446
+ )
1447
+
1448
+ return O_v̇_WL
1449
+
1450
+
1246
1451
  @jax.jit
1247
1452
  def link_contact_forces(
1248
1453
  model: js.model.JaxSimModel, data: js.data.JaxSimModelData
jaxsim/api/ode.py CHANGED
@@ -8,7 +8,6 @@ import jaxsim.rbda
8
8
  import jaxsim.typing as jtp
9
9
  from jaxsim.integrators import Time
10
10
  from jaxsim.math import Quaternion
11
- from jaxsim.utils import Mutability
12
11
 
13
12
  from .common import VelRepr
14
13
  from .ode_data import ODEState
@@ -324,7 +324,7 @@ class ExplicitRungeKutta(Integrator[PyTreeType, PyTreeType], Generic[PyTreeType]
324
324
  def post_process_state(
325
325
  cls, x0: State, t0: Time, xf: NextState, dt: TimeStep
326
326
  ) -> NextState:
327
- """
327
+ r"""
328
328
  Post-process the integrated state at :math:`t_f = t_0 + \Delta t`.
329
329
 
330
330
  Args:
@@ -529,7 +529,7 @@ class ExplicitRungeKutta(Integrator[PyTreeType, PyTreeType], Generic[PyTreeType]
529
529
  # Return the index of the row of A providing the fsal derivative (that is the
530
530
  # possibly intermediate kᵢ derivative).
531
531
  # Note that if multiple rows match (it should not), we return the first match.
532
- return True, int(jnp.where(rows_of_A_with_fsal == True)[0].tolist()[0])
532
+ return True, int(jnp.where(rows_of_A_with_fsal)[0].tolist()[0])
533
533
 
534
534
 
535
535
  class ExplicitRungeKuttaSO3Mixin:
jaxsim/math/transform.py CHANGED
@@ -1,4 +1,3 @@
1
- import jax
2
1
  import jax.numpy as jnp
3
2
  import jaxlie
4
3
 
jaxsim/mujoco/loaders.py CHANGED
@@ -102,7 +102,7 @@ class RodModelToMjcf:
102
102
 
103
103
  if root.find(f".//joint[@name='{floating_joint_name}']") is not None:
104
104
  msg = f"The URDF already has a floating joint '{floating_joint_name}'"
105
- warnings.warn(msg)
105
+ warnings.warn(msg, stacklevel=2)
106
106
  return ET.tostring(root, pretty_print=True).decode()
107
107
 
108
108
  # Create the "world" link if it doesn't exist.
jaxsim/mujoco/model.py CHANGED
@@ -7,6 +7,8 @@ import numpy as np
7
7
  import numpy.typing as npt
8
8
  from scipy.spatial.transform import Rotation
9
9
 
10
+ import jaxsim.typing as jtp
11
+
10
12
  HeightmapCallable = Callable[[jtp.FloatLike, jtp.FloatLike], jtp.FloatLike]
11
13
 
12
14
 
@@ -268,7 +268,7 @@ class KinematicGraph:
268
268
 
269
269
  # Return early if there is no action to take
270
270
  if len(joint_names_to_remove) == 0:
271
- logging.info(f"The kinematic graph doesn't need to be reduced")
271
+ logging.info("The kinematic graph doesn't need to be reduced")
272
272
  return copy.deepcopy(self)
273
273
 
274
274
  # Check if all considered joints are part of the full kinematic graph
@@ -1,6 +1,5 @@
1
1
  import abc
2
2
  import contextlib
3
- import copy
4
3
  import dataclasses
5
4
  import functools
6
5
  from collections.abc import Iterator
@@ -1,6 +1,6 @@
1
1
  Metadata-Version: 2.1
2
2
  Name: jaxsim
3
- Version: 0.2.dev376
3
+ Version: 0.2.dev394
4
4
  Summary: A physics engine in reduced coordinates implemented with JAX.
5
5
  Home-page: https://github.com/ami-iit/jaxsim
6
6
  Author: Diego Ferigo
@@ -1,21 +1,21 @@
1
1
  jaxsim/__init__.py,sha256=OcrfoYS1DGcmAGqu2AqlCTiUVxcpi-IsVwcr_16x74Q,1789
2
- jaxsim/_version.py,sha256=nAy-z_b2P4v0CvZeZkkzcsMlBO4LKnDdLnFE2Kq0a4U,423
2
+ jaxsim/_version.py,sha256=so5jZFKl8aDmZRylEyYqJKNNSSEg2aGlO-xfDv0En8w,423
3
3
  jaxsim/logging.py,sha256=c4zhwBKf9eAYAHVp62kTEllqdsZgh0K-kPKVy8L3elU,1584
4
4
  jaxsim/typing.py,sha256=MeuOCQtLAr-sPkvB_sU8FtwGNRirz1auCwIgRC-QZl8,646
5
5
  jaxsim/api/__init__.py,sha256=fNTCPUeDfOAizRd4RsW3Epv0sLTu0KJGoFRSEsi75VM,162
6
6
  jaxsim/api/com.py,sha256=Qtm_6qpiK4WtDVn6JMUHa8DySgBl9CjgKCybJqZ58Lc,7379
7
- jaxsim/api/common.py,sha256=6oqZO-QTYr2mpMx5qRrAnCIjQpjIJVe7MlavNFIKbNA,6638
7
+ jaxsim/api/common.py,sha256=DV-WZG28sikXopNv458aYvpLjmiAtFr5LRscOwXusuk,6640
8
8
  jaxsim/api/contact.py,sha256=Ve4ZOWkLEBRgK3KhtICxKY7YzsxYvc3lO-pPRBjqSnY,8659
9
- jaxsim/api/data.py,sha256=1AJyKjmXdsWEf_CkvOXRmvRsDZamG706mAAg1Gttll0,26773
9
+ jaxsim/api/data.py,sha256=cPFy6TTm0rNpDk1O0ZxOpvBwWVPu6V14XLRMeC7x81Q,26786
10
10
  jaxsim/api/joint.py,sha256=q31Kp3Cqv-yTcxijjzbj_QADFnGQyjb2al9fYZtzedo,4763
11
11
  jaxsim/api/kin_dyn_parameters.py,sha256=G4mtSi8fElYe0yttLgsxSOPf7vcK-yqTu06Aa5SSrYg,26012
12
- jaxsim/api/link.py,sha256=LZVcQhQsTKsfR13KewFtEMYu4siVJl7mqoDwYsoFFes,9240
13
- jaxsim/api/model.py,sha256=_waDChFZsHRbKOX6dkajRQxGkhqXFRMiMp3JXMqZ-MU,44089
14
- jaxsim/api/ode.py,sha256=rbSruK0Dkp09oBgHbB_-NrZS4o2tY9geK0yLLJfXzpM,9821
12
+ jaxsim/api/link.py,sha256=rypTwkMf9HJ5UuAtHRJh0LqqdJWcLKTtTjWcjduEsF0,9842
13
+ jaxsim/api/model.py,sha256=u7CZTNc0UY0ZVpUEW-RsZi2UysyzbK06zvSPsdOlPYQ,52269
14
+ jaxsim/api/ode.py,sha256=6l-6i2YHagsQvR8Ac-_fmO6P0hBVT6NkHhwXnrdITEg,9785
15
15
  jaxsim/api/ode_data.py,sha256=dwRFVPJ30XMmdUbPXEu7YxsQ97jZP4L4fd5ZzhrO5Ys,22184
16
16
  jaxsim/api/references.py,sha256=Lvskf17r619KKxwCJP7hAAty2kaXgDXJX1uKqoDIDgo,15483
17
17
  jaxsim/integrators/__init__.py,sha256=hxvOD-VK_mmd6v31wtC-nb28AYve1gLuZCNLV9wS-Kg,103
18
- jaxsim/integrators/common.py,sha256=APmQVXKdN9JMIq7wrVKq2HlI1UKpqvLqaTqAq0VfJJ0,20700
18
+ jaxsim/integrators/common.py,sha256=9HXRVFo95Mpt6RcVhBrOfvOO7mDxqbkXeg_lKUibEFY,20693
19
19
  jaxsim/integrators/fixed_step.py,sha256=JXaEyEzfSiYea0GnPA7l27J3X0YPB0e25D4qfrxAvzQ,2766
20
20
  jaxsim/integrators/variable_step.py,sha256=jq3PStzFiMciU7lux6CTj4B3gVOfSpYgK2oz2yzIbdo,21380
21
21
  jaxsim/math/__init__.py,sha256=inJ9nRFkqstuGa8OyFkfWVudo5U9Ug4WgDBuKva8AIA,337
@@ -26,14 +26,14 @@ jaxsim/math/joint_model.py,sha256=LKLB26VMz6vx9JLdFUWhGyrElYFEQV-bJiQO5kaZUGY,10
26
26
  jaxsim/math/quaternion.py,sha256=X9b8jHf0QemKUjIZSnXRJc3DdMr42CBhBy_mi9_X_AM,5068
27
27
  jaxsim/math/rotation.py,sha256=Z90daUjGpuNEVLfWB3SVtM9EtwAIaneVj9A9UpWXqhA,2182
28
28
  jaxsim/math/skew.py,sha256=oOGSSR8PUGROl6IJFlrmu6K3gPH-u16hUPfKIkcVv9o,1177
29
- jaxsim/math/transform.py,sha256=nqH6ofde6VWjfHihmYdXvDxKFChpOPH6AsoqkUI1Og0,2928
29
+ jaxsim/math/transform.py,sha256=boeuN8df4Yd9NvS64g-xUYoNqG91YafYLam4iITFJVg,2917
30
30
  jaxsim/mujoco/__init__.py,sha256=Zo5GAlN1DYKvX8s1hu1j6HntKIbBMLB9Puv9ouaNAZ8,158
31
31
  jaxsim/mujoco/__main__.py,sha256=GBmB7J-zj75ZnFyuAAmpSOpbxi_HhHhWJeot3ljGDJY,5291
32
- jaxsim/mujoco/loaders.py,sha256=IGhchLIzINXDm8nDIsy1qIrffoiOpr8Hs36JTOOYVhg,17392
33
- jaxsim/mujoco/model.py,sha256=GgDlr7fSSEnkyqziPLLQaippMr4wRhfTo39DstD9Qik,12088
32
+ jaxsim/mujoco/loaders.py,sha256=PG6TrmurdF99B_HJW39daNXMYlwGy3JMofb4oTRwPLc,17406
33
+ jaxsim/mujoco/model.py,sha256=ErL4X4QWPCJJJjCAMHsFsksYTgIpmV_M8xWPZc-gQcA,12117
34
34
  jaxsim/mujoco/visualizer.py,sha256=-qg26t5tleTva6zzQmc5SdnlC8XZ1ZAwZ_lDjdwHJ0A,4400
35
35
  jaxsim/parsers/__init__.py,sha256=sonYi-bBWAoB04kp1mxT4uIORxjb7SdZ0ukGPmVx98Y,44
36
- jaxsim/parsers/kinematic_graph.py,sha256=2B5gtUboiSVJIm6PegbwHb5g_iXltG0R9_7h8RJ-92M,23785
36
+ jaxsim/parsers/kinematic_graph.py,sha256=_ZJr-u1m64qPCeY6BHTI56dSOWhOGfbg2HN49XbTXhA,23784
37
37
  jaxsim/parsers/descriptions/__init__.py,sha256=EbTfnrK3oCxA3pNv--YUwllJ6uICENvFgAdRbYtS9ts,238
38
38
  jaxsim/parsers/descriptions/collision.py,sha256=HUWwuRgI9KznY29FFw1_zU3bGigDEezrcPOJSxSJGNU,3382
39
39
  jaxsim/parsers/descriptions/joint.py,sha256=hpH0ANvIhbEQk-NGRmWIvPv3lXW385TBIMWNgz5rzM4,4106
@@ -55,10 +55,10 @@ jaxsim/terrain/__init__.py,sha256=f7lVX-iNpH_wkkjef9Qpjh19TTAUOQw76EiLYJDVizc,78
55
55
  jaxsim/terrain/terrain.py,sha256=q0xkWqEShVq-p1j2abTLZq8sEhjyJwquxQKm80PaHhM,2161
56
56
  jaxsim/utils/__init__.py,sha256=tnQq1_CavdfeKaLYt3pmO7Jk4MU2RwwQU_qICkjyoTY,197
57
57
  jaxsim/utils/hashless.py,sha256=bFIwKeo9KiWwsY8QM55duEGGQOyyJ4jQyPcuqTLEp5k,297
58
- jaxsim/utils/jaxsim_dataclass.py,sha256=9FtzgXQPSa6AN26FleDgXGsJMse4dtVACDESrn0g3bw,11359
58
+ jaxsim/utils/jaxsim_dataclass.py,sha256=T8nZolb563mYJD7YvTmYW-z-hpkEiaK3cDbYHqwtqRc,11347
59
59
  jaxsim/utils/tracing.py,sha256=KDMoyVPlu2NJvFkhtZwq5AkqMMgajt3munvJom-vEjQ,650
60
- jaxsim-0.2.dev376.dist-info/LICENSE,sha256=EsU2z6_sWW4Zduzq3goVWjZoCZVKQsM4H_y0o7oRA7Q,1547
61
- jaxsim-0.2.dev376.dist-info/METADATA,sha256=eWcinEhSdothvx37-yafMhBddfT5s0fIo4veqCLNnI8,7630
62
- jaxsim-0.2.dev376.dist-info/WHEEL,sha256=GJ7t_kWBFywbagK5eo9IoUwLW6oyOeTKmQ-9iHFVNxQ,92
63
- jaxsim-0.2.dev376.dist-info/top_level.txt,sha256=LxGMA8FLtXjQ6oI7N5gd_R_oSUHxpXxUEOfT1xS_ni0,7
64
- jaxsim-0.2.dev376.dist-info/RECORD,,
60
+ jaxsim-0.2.dev394.dist-info/LICENSE,sha256=EsU2z6_sWW4Zduzq3goVWjZoCZVKQsM4H_y0o7oRA7Q,1547
61
+ jaxsim-0.2.dev394.dist-info/METADATA,sha256=MAzjWBb9UwRC3HkwkBP6ivGKFF7qKmbUT0oGDyB0VJE,7630
62
+ jaxsim-0.2.dev394.dist-info/WHEEL,sha256=GJ7t_kWBFywbagK5eo9IoUwLW6oyOeTKmQ-9iHFVNxQ,92
63
+ jaxsim-0.2.dev394.dist-info/top_level.txt,sha256=LxGMA8FLtXjQ6oI7N5gd_R_oSUHxpXxUEOfT1xS_ni0,7
64
+ jaxsim-0.2.dev394.dist-info/RECORD,,