jaxsim 0.6.2.dev181__py3-none-any.whl → 0.6.2.dev194__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
@@ -17,5 +17,5 @@ __version__: str
17
17
  __version_tuple__: VERSION_TUPLE
18
18
  version_tuple: VERSION_TUPLE
19
19
 
20
- __version__ = version = '0.6.2.dev181'
21
- __version_tuple__ = version_tuple = (0, 6, 2, 'dev181')
20
+ __version__ = version = '0.6.2.dev194'
21
+ __version_tuple__ = version_tuple = (0, 6, 2, 'dev194')
jaxsim/api/common.py CHANGED
@@ -121,14 +121,8 @@ class ModelDataWithVelocityRepresentation(JaxsimDataclass, abc.ABC):
121
121
  The 6D quantity in the other representation.
122
122
  """
123
123
 
124
- W_array = array.squeeze()
125
- W_H_O = transform.squeeze()
126
-
127
- if W_array.size != 6:
128
- raise ValueError(W_array.size, 6)
129
-
130
- if W_H_O.shape != (4, 4):
131
- raise ValueError(W_H_O.shape, (4, 4))
124
+ W_array = array
125
+ W_H_O = transform
132
126
 
133
127
  match other_representation:
134
128
 
@@ -139,25 +133,24 @@ class ModelDataWithVelocityRepresentation(JaxsimDataclass, abc.ABC):
139
133
 
140
134
  if not is_force:
141
135
  O_Xv_W = Adjoint.from_transform(transform=W_H_O, inverse=True)
142
- O_array = O_Xv_W @ W_array
136
+ O_array = jnp.einsum("...ij,...j->...i", O_Xv_W, W_array)
143
137
 
144
138
  else:
145
- O_Xf_W = Adjoint.from_transform(transform=W_H_O).T
146
- O_array = O_Xf_W @ W_array
139
+ O_Xf_W = Adjoint.from_transform(transform=W_H_O).swapaxes(-1, -2)
140
+ O_array = jnp.einsum("...ij,...j->...i", O_Xf_W, W_array)
147
141
 
148
142
  return O_array
149
143
 
150
144
  case VelRepr.Mixed:
151
- W_p_O = W_H_O[0:3, 3]
152
- W_H_OW = jnp.eye(4).at[0:3, 3].set(W_p_O)
145
+ W_H_OW = W_H_O.at[..., 0:3, 0:3].set(jnp.eye(3))
153
146
 
154
147
  if not is_force:
155
148
  OW_Xv_W = Adjoint.from_transform(transform=W_H_OW, inverse=True)
156
- OW_array = OW_Xv_W @ W_array
149
+ OW_array = jnp.einsum("...ij,...j->...i", OW_Xv_W, W_array)
157
150
 
158
151
  else:
159
- OW_Xf_W = Adjoint.from_transform(transform=W_H_OW).T
160
- OW_array = OW_Xf_W @ W_array
152
+ OW_Xf_W = Adjoint.from_transform(transform=W_H_OW).swapaxes(-1, -2)
153
+ OW_array = jnp.einsum("...ij,...j->...i", OW_Xf_W, W_array)
161
154
 
162
155
  return OW_array
163
156
 
@@ -188,45 +181,40 @@ class ModelDataWithVelocityRepresentation(JaxsimDataclass, abc.ABC):
188
181
  The 6D quantity in the inertial-fixed representation.
189
182
  """
190
183
 
191
- W_array = array.squeeze()
192
- W_H_O = transform.squeeze()
193
-
194
- if W_array.size != 6:
195
- raise ValueError(W_array.size, 6)
196
-
197
- if W_H_O.shape != (4, 4):
198
- raise ValueError(W_H_O.shape, (4, 4))
184
+ O_array = array
185
+ W_H_O = transform
199
186
 
200
187
  match other_representation:
201
188
  case VelRepr.Inertial:
202
- W_array = array
203
- return W_array
189
+ return O_array
204
190
 
205
191
  case VelRepr.Body:
206
- O_array = array
207
192
 
208
193
  if not is_force:
209
- W_Xv_O: jtp.Array = Adjoint.from_transform(W_H_O)
210
- W_array = W_Xv_O @ O_array
194
+ W_Xv_O = Adjoint.from_transform(W_H_O)
195
+ W_array = jnp.einsum("...ij,...j->...i", W_Xv_O, O_array)
211
196
 
212
197
  else:
213
- W_Xf_O = Adjoint.from_transform(transform=W_H_O, inverse=True).T
214
- W_array = W_Xf_O @ O_array
198
+ W_Xf_O = Adjoint.from_transform(
199
+ transform=W_H_O, inverse=True
200
+ ).swapaxes(-1, -2)
201
+ W_array = jnp.einsum("...ij,...j->...i", W_Xf_O, O_array)
215
202
 
216
203
  return W_array
217
204
 
218
205
  case VelRepr.Mixed:
219
- BW_array = array
220
- W_p_O = W_H_O[0:3, 3]
221
- W_H_OW = jnp.eye(4).at[0:3, 3].set(W_p_O)
206
+
207
+ W_H_OW = W_H_O.at[..., 0:3, 0:3].set(jnp.eye(3))
222
208
 
223
209
  if not is_force:
224
- W_Xv_BW: jtp.Array = Adjoint.from_transform(W_H_OW)
225
- W_array = W_Xv_BW @ BW_array
210
+ W_Xv_BW = Adjoint.from_transform(W_H_OW)
211
+ W_array = jnp.einsum("...ij,...j->...i", W_Xv_BW, O_array)
226
212
 
227
213
  else:
228
- W_Xf_BW = Adjoint.from_transform(transform=W_H_OW, inverse=True).T
229
- W_array = W_Xf_BW @ BW_array
214
+ W_Xf_BW = Adjoint.from_transform(
215
+ transform=W_H_OW, inverse=True
216
+ ).swapaxes(-1, -2)
217
+ W_array = jnp.einsum("...ij,...j->...i", W_Xf_BW, O_array)
230
218
 
231
219
  return W_array
232
220
 
jaxsim/api/data.py CHANGED
@@ -265,14 +265,14 @@ class JaxSimModelData(common.ModelDataWithVelocityRepresentation):
265
265
  """
266
266
 
267
267
  # Extract the base quaternion.
268
- W_Q_B = self.base_quaternion.squeeze()
268
+ W_Q_B = self.base_quaternion
269
269
 
270
270
  # Always normalize the quaternion to avoid numerical issues.
271
271
  # If the active scheme does not integrate the quaternion on its manifold,
272
272
  # we introduce a Baumgarte stabilization to let the quaternion converge to
273
273
  # a unit quaternion. In this case, it is not guaranteed that the quaternion
274
274
  # stored in the state is a unit quaternion.
275
- norm = jaxsim.math.safe_norm(W_Q_B)
275
+ norm = jaxsim.math.safe_norm(W_Q_B, axis=-1, keepdims=True)
276
276
  W_Q_B = W_Q_B / (norm + jnp.finfo(float).eps * (norm == 0))
277
277
  return W_Q_B
278
278
 
@@ -285,11 +285,8 @@ class JaxSimModelData(common.ModelDataWithVelocityRepresentation):
285
285
  The base 6D velocity in the active representation.
286
286
  """
287
287
 
288
- W_v_WB = jnp.hstack(
289
- [
290
- self._base_linear_velocity,
291
- self._base_angular_velocity,
292
- ]
288
+ W_v_WB = jnp.concatenate(
289
+ [self._base_linear_velocity, self._base_angular_velocity], axis=-1
293
290
  )
294
291
 
295
292
  W_H_B = self._base_transform
@@ -363,7 +360,7 @@ class JaxSimModelData(common.ModelDataWithVelocityRepresentation):
363
360
 
364
361
  W_Q_B = jnp.array(base_quaternion, dtype=float)
365
362
 
366
- norm = jaxsim.math.safe_norm(W_Q_B)
363
+ norm = jaxsim.math.safe_norm(W_Q_B, axis=-1)
367
364
  W_Q_B = W_Q_B / (norm + jnp.finfo(float).eps * (norm == 0))
368
365
 
369
366
  return self.replace(validate=True, base_quaternion=W_Q_B)
@@ -404,6 +401,12 @@ class JaxSimModelData(common.ModelDataWithVelocityRepresentation):
404
401
  """
405
402
  Replace the attributes of the `JaxSimModelData` object.
406
403
  """
404
+
405
+ # Extract the batch size.
406
+ batch_size = (
407
+ self._base_transform.shape[0] if self._base_transform.ndim > 2 else 1
408
+ )
409
+
407
410
  if joint_positions is None:
408
411
  joint_positions = self.joint_positions
409
412
  if joint_velocities is None:
@@ -413,6 +416,14 @@ class JaxSimModelData(common.ModelDataWithVelocityRepresentation):
413
416
  if base_position is None:
414
417
  base_position = self.base_position
415
418
 
419
+ # Normalize the quaternion to avoid numerical issues.
420
+ base_quaternion_norm = jaxsim.math.safe_norm(
421
+ base_quaternion, axis=-1, keepdims=True
422
+ )
423
+ base_quaternion = base_quaternion / jnp.where(
424
+ base_quaternion_norm == 0, 1.0, base_quaternion_norm
425
+ )
426
+
416
427
  joint_positions = jnp.atleast_1d(joint_positions.squeeze()).astype(float)
417
428
  joint_velocities = jnp.atleast_1d(joint_velocities.squeeze()).astype(float)
418
429
  base_quaternion = jnp.atleast_1d(base_quaternion.squeeze()).astype(float)
@@ -421,44 +432,69 @@ class JaxSimModelData(common.ModelDataWithVelocityRepresentation):
421
432
  base_transform = jaxsim.math.Transform.from_quaternion_and_translation(
422
433
  translation=base_position, quaternion=base_quaternion
423
434
  )
424
- joint_transforms = model.kin_dyn_parameters.joint_transforms(
425
- joint_positions=joint_positions, base_transform=base_transform
435
+
436
+ joint_transforms = jax.vmap(model.kin_dyn_parameters.joint_transforms)(
437
+ joint_positions=jnp.broadcast_to(
438
+ joint_positions, (batch_size, model.dofs())
439
+ ),
440
+ base_transform=jnp.broadcast_to(base_transform, (batch_size, 4, 4)),
426
441
  )
427
442
 
428
443
  if base_linear_velocity is None and base_angular_velocity is None:
429
- base_linear_velocity = self._base_linear_velocity
430
- base_angular_velocity = self._base_angular_velocity
444
+ base_linear_velocity_inertial = self._base_linear_velocity
445
+ base_angular_velocity_inertial = self._base_angular_velocity
431
446
  else:
432
447
  if base_linear_velocity is None:
433
448
  base_linear_velocity = self.base_velocity[:3]
434
449
  if base_angular_velocity is None:
435
450
  base_angular_velocity = self.base_velocity[3:]
451
+
436
452
  base_linear_velocity = jnp.atleast_1d(base_linear_velocity.squeeze())
437
453
  base_angular_velocity = jnp.atleast_1d(base_angular_velocity.squeeze())
454
+
438
455
  W_v_WB = JaxSimModelData.other_representation_to_inertial(
439
456
  array=jnp.hstack([base_linear_velocity, base_angular_velocity]),
440
457
  other_representation=self.velocity_representation,
441
458
  transform=base_transform,
442
459
  is_force=False,
443
460
  ).astype(float)
444
- base_linear_velocity, base_angular_velocity = W_v_WB[:3], W_v_WB[3:]
445
-
446
- link_transforms, link_velocities = jaxsim.rbda.forward_kinematics_model(
447
- model=model,
448
- base_position=base_position,
449
- base_quaternion=base_quaternion,
450
- joint_positions=joint_positions,
451
- joint_velocities=joint_velocities,
452
- base_linear_velocity_inertial=base_linear_velocity,
453
- base_angular_velocity_inertial=base_angular_velocity,
461
+
462
+ base_linear_velocity_inertial, base_angular_velocity_inertial = (
463
+ W_v_WB[..., :3],
464
+ W_v_WB[..., 3:],
465
+ )
466
+
467
+ link_transforms, link_velocities = jax.vmap(
468
+ jaxsim.rbda.forward_kinematics_model, in_axes=(None,)
469
+ )(
470
+ model,
471
+ base_position=jnp.broadcast_to(base_position, (batch_size, 3)),
472
+ base_quaternion=jnp.broadcast_to(base_quaternion, (batch_size, 4)),
473
+ joint_positions=jnp.broadcast_to(
474
+ joint_positions, (batch_size, model.dofs())
475
+ ),
476
+ joint_velocities=jnp.broadcast_to(
477
+ joint_velocities, (batch_size, model.dofs())
478
+ ),
479
+ base_linear_velocity_inertial=jnp.broadcast_to(
480
+ base_linear_velocity_inertial, (batch_size, 3)
481
+ ),
482
+ base_angular_velocity_inertial=jnp.broadcast_to(
483
+ base_angular_velocity_inertial, (batch_size, 3)
484
+ ),
454
485
  )
455
486
 
487
+ # Adjust the output shapes.
488
+ if batch_size == 1:
489
+ link_transforms = link_transforms.reshape(link_transforms.shape[1:])
490
+ link_velocities = link_velocities.reshape(link_velocities.shape[1:])
491
+
456
492
  return super().replace(
457
493
  _joint_positions=joint_positions,
458
494
  _joint_velocities=joint_velocities,
459
495
  _base_quaternion=base_quaternion,
460
- _base_linear_velocity=base_linear_velocity,
461
- _base_angular_velocity=base_angular_velocity,
496
+ _base_linear_velocity=base_linear_velocity_inertial,
497
+ _base_angular_velocity=base_angular_velocity_inertial,
462
498
  _base_position=base_position,
463
499
  _base_transform=base_transform,
464
500
  _joint_transforms=joint_transforms,
jaxsim/api/integrators.py CHANGED
@@ -58,7 +58,7 @@ def semi_implicit_euler_integration(
58
58
  W_p_B = data.base_position + dt * W_ṗ_B
59
59
  W_Q_B = data.base_orientation + dt * W_Q̇_B
60
60
 
61
- base_quaternion_norm = jaxsim.math.safe_norm(W_Q_B)
61
+ base_quaternion_norm = jaxsim.math.safe_norm(W_Q_B, axis=-1)
62
62
 
63
63
  W_Q_B = W_Q_B / jnp.where(base_quaternion_norm == 0, 1.0, base_quaternion_norm)
64
64
 
@@ -104,7 +104,7 @@ def rk4_integration(
104
104
  joint_torques=joint_torques,
105
105
  )
106
106
 
107
- base_quaternion_norm = jaxsim.math.safe_norm(data._base_quaternion)
107
+ base_quaternion_norm = jaxsim.math.safe_norm(data._base_quaternion, axis=-1)
108
108
  base_quaternion = data._base_quaternion / jnp.where(
109
109
  base_quaternion_norm == 0, 1.0, base_quaternion_norm
110
110
  )
jaxsim/api/model.py CHANGED
@@ -124,6 +124,7 @@ class JaxSimModel(JaxsimDataclass):
124
124
  integrator: IntegratorType | None = None,
125
125
  is_urdf: bool | None = None,
126
126
  considered_joints: Sequence[str] | None = None,
127
+ gravity: jtp.FloatLike = jaxsim.math.STANDARD_GRAVITY,
127
128
  ) -> JaxSimModel:
128
129
  """
129
130
  Build a Model object from a model description.
@@ -148,6 +149,7 @@ class JaxSimModel(JaxsimDataclass):
148
149
  This is usually automatically inferred.
149
150
  considered_joints:
150
151
  The list of joints to consider. If None, all joints are considered.
152
+ gravity: The gravity constant. Normally passed as a positive value.
151
153
 
152
154
  Returns:
153
155
  The built Model object.
@@ -177,6 +179,7 @@ class JaxSimModel(JaxsimDataclass):
177
179
  contact_model=contact_model,
178
180
  contacts_params=contact_params,
179
181
  integrator=integrator,
182
+ gravity=gravity,
180
183
  )
181
184
 
182
185
  # Store the origin of the model, in case downstream logic needs it.
@@ -2066,14 +2069,12 @@ def step(
2066
2069
  )
2067
2070
 
2068
2071
  # Get the external forces in inertial-fixed representation.
2069
- W_f_L_external = jax.vmap(
2070
- lambda f_L, W_H_L: js.data.JaxSimModelData.other_representation_to_inertial(
2071
- f_L,
2072
- other_representation=data.velocity_representation,
2073
- transform=W_H_L,
2074
- is_force=True,
2075
- )
2076
- )(O_f_L_external, data._link_transforms)
2072
+ W_f_L_external = js.data.JaxSimModelData.other_representation_to_inertial(
2073
+ O_f_L_external,
2074
+ other_representation=data.velocity_representation,
2075
+ transform=data._link_transforms,
2076
+ is_force=True,
2077
+ )
2077
2078
 
2078
2079
  τ_references = jnp.atleast_1d(
2079
2080
  jnp.array(joint_force_references, dtype=float).squeeze()
jaxsim/api/references.py CHANGED
@@ -434,24 +434,17 @@ class JaxSimModelReferences(js.common.ModelDataWithVelocityRepresentation):
434
434
  if not_tracing(forces) and not data.valid(model=model):
435
435
  raise ValueError("The provided data is not valid for the model")
436
436
 
437
- # Helper function to convert a single 6D force to the inertial representation
438
- # considering as body the link (i.e. L_f_L and LW_f_L).
439
- def convert_using_link_frame(
440
- f_L: jtp.MatrixLike, W_H_L: jtp.ArrayLike
441
- ) -> jtp.Matrix:
442
-
443
- return jax.vmap(
444
- lambda f_L, W_H_L: JaxSimModelReferences.other_representation_to_inertial(
445
- array=f_L,
446
- other_representation=self.velocity_representation,
447
- transform=W_H_L,
448
- is_force=True,
449
- )
450
- )(f_L, W_H_L)
437
+ W_H_L = data._link_transforms
451
438
 
439
+ # Convert a single 6D force to the inertial representation
440
+ # considering as body the link (i.e. L_f_L and LW_f_L).
452
441
  # The f_L input is either L_f_L or LW_f_L, depending on the representation.
453
- W_H_L = data._link_transforms
454
- W_f_L = convert_using_link_frame(f_L=f_L, W_H_L=W_H_L[link_idxs, :, :])
442
+ W_f_L = JaxSimModelReferences.other_representation_to_inertial(
443
+ array=f_L,
444
+ other_representation=self.velocity_representation,
445
+ transform=W_H_L[link_idxs] if model.number_of_links() > 1 else W_H_L,
446
+ is_force=True,
447
+ )
455
448
 
456
449
  return replace(forces=self._link_forces.at[link_idxs, :].set(W_f0_L + W_f_L))
457
450
 
jaxsim/math/adjoint.py CHANGED
@@ -55,13 +55,13 @@ class Adjoint:
55
55
  The 6x6 adjoint matrix.
56
56
  """
57
57
 
58
- A_H_B = jnp.reshape(transform, (-1, 4, 4))
58
+ A_H_B = transform
59
59
 
60
60
  return (
61
61
  jaxlie.SE3.from_matrix(matrix=A_H_B).adjoint()
62
62
  if not inverse
63
63
  else jaxlie.SE3.from_matrix(matrix=A_H_B).inverse().adjoint()
64
- ).reshape(transform.shape[:-2] + (6, 6))
64
+ )
65
65
 
66
66
  @staticmethod
67
67
  def from_rotation_and_translation(
jaxsim/math/transform.py CHANGED
@@ -36,8 +36,8 @@ class Transform:
36
36
  W_Q_B = jnp.array(quaternion).astype(float)
37
37
  W_p_B = jnp.array(translation).astype(float)
38
38
 
39
- assert W_p_B.size == 3
40
- assert W_Q_B.size == 4
39
+ assert W_p_B.shape[-1] == 3
40
+ assert W_Q_B.shape[-1] == 4
41
41
 
42
42
  A_R_B = jaxlie.SO3(wxyz=W_Q_B)
43
43
  A_R_B = A_R_B if not normalize_quaternion else A_R_B.normalize()
jaxsim/math/utils.py CHANGED
@@ -3,7 +3,7 @@ import jax.numpy as jnp
3
3
  import jaxsim.typing as jtp
4
4
 
5
5
 
6
- def safe_norm(array: jtp.ArrayLike, axis=None) -> jtp.Array:
6
+ def safe_norm(array: jtp.ArrayLike, *, axis=None, keepdims: bool = False) -> jtp.Array:
7
7
  """
8
8
  Compute an array norm handling NaNs and making sure that
9
9
  it is safe to get the gradient.
@@ -11,6 +11,7 @@ def safe_norm(array: jtp.ArrayLike, axis=None) -> jtp.Array:
11
11
  Args:
12
12
  array: The array for which to compute the norm.
13
13
  axis: The axis for which to compute the norm.
14
+ keepdims: Whether to keep the dimensions of the input
14
15
 
15
16
  Returns:
16
17
  The norm of the array with handling for zero arrays to avoid NaNs.
@@ -24,7 +25,7 @@ def safe_norm(array: jtp.ArrayLike, axis=None) -> jtp.Array:
24
25
  array = jnp.where(is_zero, jnp.ones_like(array), array)
25
26
 
26
27
  # Compute the norm of the array along the specified axis.
27
- norm = jnp.linalg.norm(array, axis=axis)
28
+ norm = jnp.linalg.norm(array, axis=axis, keepdims=keepdims)
28
29
 
29
30
  # Use `jnp.where` to set the norm to 0.0 where the input array was all zeros.
30
31
  # This usage supports potential batch processing for future scalability.
@@ -64,7 +64,7 @@ class MujocoVideoRecorder:
64
64
 
65
65
  self.frames = []
66
66
 
67
- self.data = [data] if data is not None else self.data
67
+ self.data = data if data is not None else self.data
68
68
  self.data = self.data if isinstance(self.data, list) else [self.data]
69
69
 
70
70
  self.model = model if model is not None else self.model
@@ -460,16 +460,12 @@ class RelaxedRigidContacts(common.ContactModel):
460
460
  CW_fl_C = solution.reshape(-1, 3)
461
461
 
462
462
  # Convert the contact forces from mixed to inertial-fixed representation.
463
- W_f_C = jax.vmap(
464
- lambda CW_fl_C, W_H_C: (
465
- ModelDataWithVelocityRepresentation.other_representation_to_inertial(
466
- array=jnp.zeros(6).at[0:3].set(CW_fl_C),
467
- transform=W_H_C,
468
- other_representation=VelRepr.Mixed,
469
- is_force=True,
470
- )
471
- ),
472
- )(CW_fl_C, W_H_C)
463
+ W_f_C = ModelDataWithVelocityRepresentation.other_representation_to_inertial(
464
+ array=jnp.zeros((W_H_C.shape[0], 6)).at[:, :3].set(CW_fl_C),
465
+ transform=W_H_C,
466
+ other_representation=VelRepr.Mixed,
467
+ is_force=True,
468
+ )
473
469
 
474
470
  return W_f_C, {}
475
471
 
@@ -703,7 +699,7 @@ class RelaxedRigidContacts(common.ContactModel):
703
699
 
704
700
  # Compute the direction of the tangential force.
705
701
  # To prevent dividing by zero, we use a switch statement.
706
- norm = jaxsim.math.safe_norm(f_tangential)
702
+ norm = jaxsim.math.safe_norm(f_tangential, axis=-1)
707
703
  f_tangential_direction = f_tangential / (
708
704
  norm + jnp.finfo(float).eps * (norm == 0)
709
705
  )
jaxsim/terrain/terrain.py CHANGED
@@ -59,7 +59,7 @@ class Terrain(abc.ABC):
59
59
  [(h_xm - h_xp) / (2 * self.delta), (h_ym - h_yp) / (2 * self.delta), 1.0]
60
60
  )
61
61
 
62
- return n / jaxsim.math.safe_norm(n)
62
+ return n / jaxsim.math.safe_norm(n, axis=-1)
63
63
 
64
64
 
65
65
  @jax_dataclasses.pytree_dataclass
@@ -1,6 +1,6 @@
1
1
  Metadata-Version: 2.2
2
2
  Name: jaxsim
3
- Version: 0.6.2.dev181
3
+ Version: 0.6.2.dev194
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,39 +1,39 @@
1
1
  jaxsim/__init__.py,sha256=b8dYoVXqtHxHcF56iM2xgKk78lsvmGrfDlvdwaGasgs,3388
2
- jaxsim/_version.py,sha256=oXtgbiCYGZB4BiX4MHVDheGcMf8oXUU_YIaqhrZ8bis,528
2
+ jaxsim/_version.py,sha256=ffq4JpA_4w3xn6_9in9QL-akBpO6VIsvArid5kGn3Jg,528
3
3
  jaxsim/exceptions.py,sha256=MQ3LRMfVMX2-g3qYj7mUVNV9OLlIA48TANJegbcQyXI,2641
4
4
  jaxsim/logging.py,sha256=STI-D_upXZYX-ZezLrlJJ0UlD5YspST0vZ_DcIwkzO4,1553
5
5
  jaxsim/typing.py,sha256=7msl8t5Jt09RNYfKdPJtpjLfWurldcycDappb045Eso,761
6
6
  jaxsim/api/__init__.py,sha256=Yck5Cr6_6yqGKwt2KicccEiy-hzIAOFA3G0sPXWQTgg,253
7
7
  jaxsim/api/actuation_model.py,sha256=L8AzxIiEquWeG8UGGJaYr2Alt4dkkOROlbsCn9hUYik,2825
8
8
  jaxsim/api/com.py,sha256=jhWcUsJtZYEQf-hnEvVuqH1KoiakBNLnTkj3PA6Cn-Q,13748
9
- jaxsim/api/common.py,sha256=jd3thxFUxcyoAMV3ZDMqfk2DlBdvWMZuI25Y0Pw5Dlo,7088
9
+ jaxsim/api/common.py,sha256=yTaRXDYkXmISBOhZ93f9TssR0p4wq7qj7B6OsvYzRME,6942
10
10
  jaxsim/api/contact.py,sha256=PpVtlb7Iw4mW0dCrGWorznzF2ai13N9SlV7DL5ecUfA,16795
11
11
  jaxsim/api/contact_model.py,sha256=gY7dRA6UIduD4OO1nRZ4VmnNXIOeDLulw5Am9gBjhUs,3334
12
- jaxsim/api/data.py,sha256=vfgzPBCbX9OUiCBKvyib2aevhZpH-MzU4ZNZsnhidQo,20790
12
+ jaxsim/api/data.py,sha256=LA3AQTuSzFvrO9acTW6NM1XZ2TtmuN5llDwQBE5IqJs,22134
13
13
  jaxsim/api/frame.py,sha256=4wg6GsyBQgYhSvc-ry_31JsaL66sZt3TtgwjB7NrHmk,14583
14
- jaxsim/api/integrators.py,sha256=O2WmwW-3lZEiA2Pp0-CsyYlnoqaz0zqqNdeCZUI5O6Q,4980
14
+ jaxsim/api/integrators.py,sha256=iEai-ie7tVmAEAHnWguLNmmaYP3oEQqQltAhMcSTN-Q,4998
15
15
  jaxsim/api/joint.py,sha256=AnqlNWmBOay-gsoo0y4AbfFQ2OCJm-8T1E0IMhZeLoY,7457
16
16
  jaxsim/api/kin_dyn_parameters.py,sha256=v1ZDb-Eqn552Zb344sJYy9e5sQT--_SYGIdtNC2JVSg,29828
17
17
  jaxsim/api/link.py,sha256=bSZOYJDY9HJMgY25VzevTTsdFZTJc6yRRpslc5FhGHE,12782
18
- jaxsim/api/model.py,sha256=TTwUTG2UscgI_C8uwVACH0LDiQrRCMGkNDamSPZAHgA,69674
18
+ jaxsim/api/model.py,sha256=rqCmzaCGN-uqAGaYteTfw9rnITJqFkDDiNiRdJAplN8,69771
19
19
  jaxsim/api/ode.py,sha256=rGOswAcchEdzx8ZfMDTR2F6AjkHymZgTTdvBbjPPpd4,5358
20
- jaxsim/api/references.py,sha256=ywNiURwZ0niYB-AzX1eoWCfdrx7TBiRyyfi_2tz-ako,20677
20
+ jaxsim/api/references.py,sha256=-vd50y3v-jkXAsILS432etIKV6e2EUE2oOeLHuUrfuQ,20399
21
21
  jaxsim/math/__init__.py,sha256=lWMswEnITzQ69O761CiHL-r7UrxyIqsHlk4YTNxtwAY,384
22
- jaxsim/math/adjoint.py,sha256=mAtCwddK1ZwpVgIp4GIY8EVAW32Z67AJl_BzREf0ih8,4731
22
+ jaxsim/math/adjoint.py,sha256=Pb0WAiAoN1ge8j_dPcdK307jmC5LzD1-DeUj9Z_NXkI,4667
23
23
  jaxsim/math/cross.py,sha256=AM4HauuuT09q2TN42qvdXhJ9LvtCh0e7ZyLjP-7sANs,1498
24
24
  jaxsim/math/inertia.py,sha256=T-iAjPYSD_72R0ZG8GDJhe5i3Jc3ojhlbBRSscTdCKg,1577
25
25
  jaxsim/math/joint_model.py,sha256=mV6F3SVHUxHcXMIw-hc4fG341R4rkK8MvRPn53HcEpg,6915
26
26
  jaxsim/math/quaternion.py,sha256=MSaZywzJDxs2te1ZELeIcupKSFIA9q_pdXy7fDAEqM4,4539
27
27
  jaxsim/math/rotation.py,sha256=TEUtT3X2tFieNxdlccup1pfaTgCTtfX-hTNotd8-nNk,1892
28
28
  jaxsim/math/skew.py,sha256=z_9YN-NDHL3n4KXWNbzTSMkFDZ0SDpz4RUcwwYFOaao,1402
29
- jaxsim/math/transform.py,sha256=We0ChLajSckxGINiJsP1a5Ur3yjg3JuweQ3kK4Woix4,3332
30
- jaxsim/math/utils.py,sha256=2id1F6QOvkHkIF3Nuxuj_tz_kI0IYlrlgVQrETmXFfI,1058
29
+ jaxsim/math/transform.py,sha256=NOWBQgL_5hVr9aHA7j0Ta-Zq_EXAKguUAx78fVPZJE4,3342
30
+ jaxsim/math/utils.py,sha256=IiH01iN54BtLnULC04pDfYe8Av99p3FGdYp2jJInm30,1166
31
31
  jaxsim/mujoco/__init__.py,sha256=1kAWzYOS7nP29S5FGyWPqiAnPf4yPSoaPW-WBGBjVV0,214
32
32
  jaxsim/mujoco/__main__.py,sha256=GBmB7J-zj75ZnFyuAAmpSOpbxi_HhHhWJeot3ljGDJY,5291
33
33
  jaxsim/mujoco/loaders.py,sha256=OCk1T11iIm3qZUibNpo_bxxLgaGSkCpLt7ae_ND0ExA,23272
34
34
  jaxsim/mujoco/model.py,sha256=bRXo1uhWDN37sP9qdejr_2vq_PXHQ7p6eyBlFff_JcE,16492
35
35
  jaxsim/mujoco/utils.py,sha256=dW3LrcM050-eVVdLuCiN3StIrTEfyk_jJyq1GiNh3fg,8396
36
- jaxsim/mujoco/visualizer.py,sha256=7CYxxqPZdCp9Wc77ZGe1t8Z_SIgBpoJAtYcvQMcCJvQ,7746
36
+ jaxsim/mujoco/visualizer.py,sha256=cmI6DhFb1XC7oEtg_wl-s-U56dWHA-F7GlBD6EDYTyA,7744
37
37
  jaxsim/parsers/__init__.py,sha256=47DEQpj8HBSa-_TImW-5JCeuQeRkm5NMpJWZG3hSuFU,0
38
38
  jaxsim/parsers/kinematic_graph.py,sha256=YkxnykmGIXYs5fSXUX1mIi81mm7lG4HMt8LyRV-31j0,35759
39
39
  jaxsim/parsers/descriptions/__init__.py,sha256=N_hp8cGI5FyEFiuNx9a-CAGCr0F0QpYEpdMHvwB7_1g,261
@@ -55,15 +55,15 @@ jaxsim/rbda/rnea.py,sha256=lMU7xxdPqGGzk0QwteB-IYjL4auHOpd78C1YqAXlp9s,7588
55
55
  jaxsim/rbda/utils.py,sha256=LDm00VhNjH2STo5y48PAtO4TC75Bybi60-Viuq3Cyss,5575
56
56
  jaxsim/rbda/contacts/__init__.py,sha256=eZKSoGpWH6IQIofhXzU-q9J00PkKTovPVnxubmzoK0E,202
57
57
  jaxsim/rbda/contacts/common.py,sha256=QSvEykjN5MuRD7Vk-rM454qBYdkwH7xZAVOBeulKAUc,5042
58
- jaxsim/rbda/contacts/relaxed_rigid.py,sha256=BTHOr0An_6K3UIkGYakaF05gkTsKHDSinDzirlvSY8o,26742
58
+ jaxsim/rbda/contacts/relaxed_rigid.py,sha256=96SZytejDL4nR7-NJ95ui6Gde5v7_L1uopAXqZ2z9tk,26627
59
59
  jaxsim/terrain/__init__.py,sha256=f7lVX-iNpH_wkkjef9Qpjh19TTAUOQw76EiLYJDVizc,78
60
- jaxsim/terrain/terrain.py,sha256=TH84r2qizMmsfW7zYLViRjacCfOkqdYHsCzD1lZEY4c,6716
60
+ jaxsim/terrain/terrain.py,sha256=so8kqVsUlPXqOKQ_UaYW6HE4XS8nTZRdFdXQyhB2tG4,6725
61
61
  jaxsim/utils/__init__.py,sha256=Y5zyoRevl3EMVQadhZ4EtSwTEkDt2vcnFoRhPJjKTZ0,215
62
62
  jaxsim/utils/jaxsim_dataclass.py,sha256=XzmZeIibcaOzaxpprsGSxH3UrM66PAO456rFV91sNXg,11453
63
63
  jaxsim/utils/tracing.py,sha256=Btwxdfhb7fJLk3r5PlQkGYj60Y2KbFT1gANGIA697FU,530
64
64
  jaxsim/utils/wrappers.py,sha256=3IMwydqFgmSPqeuUQ3PRmdhDc1IoT6XC23jPC_LjWXs,4175
65
- jaxsim-0.6.2.dev181.dist-info/LICENSE,sha256=eaYdFmdeMbiIoIiPzEK0MjP1S9wtFXjXNR5er49uLR0,1546
66
- jaxsim-0.6.2.dev181.dist-info/METADATA,sha256=PykYmopJcd0lcYxnJWi9U5cTRwJbB46pH8leBE-KyZg,19991
67
- jaxsim-0.6.2.dev181.dist-info/WHEEL,sha256=52BFRY2Up02UkjOa29eZOS2VxUrpPORXg1pkohGGUS8,91
68
- jaxsim-0.6.2.dev181.dist-info/top_level.txt,sha256=LxGMA8FLtXjQ6oI7N5gd_R_oSUHxpXxUEOfT1xS_ni0,7
69
- jaxsim-0.6.2.dev181.dist-info/RECORD,,
65
+ jaxsim-0.6.2.dev194.dist-info/LICENSE,sha256=eaYdFmdeMbiIoIiPzEK0MjP1S9wtFXjXNR5er49uLR0,1546
66
+ jaxsim-0.6.2.dev194.dist-info/METADATA,sha256=fu2E38Wz5QqAZwEuZ3_FKromc9d2fFyc9LYc2P_Xz-4,19991
67
+ jaxsim-0.6.2.dev194.dist-info/WHEEL,sha256=beeZ86-EfXScwlR_HKu4SllMC9wUEj_8Z_4FJ3egI2w,91
68
+ jaxsim-0.6.2.dev194.dist-info/top_level.txt,sha256=LxGMA8FLtXjQ6oI7N5gd_R_oSUHxpXxUEOfT1xS_ni0,7
69
+ jaxsim-0.6.2.dev194.dist-info/RECORD,,
@@ -1,5 +1,5 @@
1
1
  Wheel-Version: 1.0
2
- Generator: setuptools (76.0.0)
2
+ Generator: setuptools (76.1.0)
3
3
  Root-Is-Purelib: true
4
4
  Tag: py3-none-any
5
5