jaxsim 0.6.2.dev182__py3-none-any.whl → 0.6.2.dev225__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.
@@ -0,0 +1,448 @@
1
+ from __future__ import annotations
2
+
3
+ import dataclasses
4
+ import functools
5
+
6
+ import jax
7
+ import jax.numpy as jnp
8
+ import jax_dataclasses
9
+
10
+ import jaxsim.api as js
11
+ import jaxsim.math
12
+ import jaxsim.typing as jtp
13
+ from jaxsim import logging
14
+ from jaxsim.terrain import Terrain
15
+
16
+ from . import common
17
+
18
+ try:
19
+ from typing import Self
20
+ except ImportError:
21
+ from typing_extensions import Self
22
+
23
+
24
+ @jax_dataclasses.pytree_dataclass
25
+ class SoftContactsParams(common.ContactsParams):
26
+ """Parameters of the soft contacts model."""
27
+
28
+ K: jtp.Float = dataclasses.field(
29
+ default_factory=lambda: jnp.array(1e6, dtype=float)
30
+ )
31
+
32
+ D: jtp.Float = dataclasses.field(
33
+ default_factory=lambda: jnp.array(2000, dtype=float)
34
+ )
35
+
36
+ mu: jtp.Float = dataclasses.field(
37
+ default_factory=lambda: jnp.array(0.5, dtype=float)
38
+ )
39
+
40
+ p: jtp.Float = dataclasses.field(
41
+ default_factory=lambda: jnp.array(0.5, dtype=float)
42
+ )
43
+
44
+ q: jtp.Float = dataclasses.field(
45
+ default_factory=lambda: jnp.array(0.5, dtype=float)
46
+ )
47
+
48
+ def __hash__(self) -> int:
49
+
50
+ from jaxsim.utils.wrappers import HashedNumpyArray
51
+
52
+ return hash(
53
+ (
54
+ HashedNumpyArray.hash_of_array(self.K),
55
+ HashedNumpyArray.hash_of_array(self.D),
56
+ HashedNumpyArray.hash_of_array(self.mu),
57
+ HashedNumpyArray.hash_of_array(self.p),
58
+ HashedNumpyArray.hash_of_array(self.q),
59
+ )
60
+ )
61
+
62
+ def __eq__(self, other: SoftContactsParams) -> bool:
63
+
64
+ if not isinstance(other, SoftContactsParams):
65
+ return False
66
+
67
+ return hash(self) == hash(other)
68
+
69
+ @classmethod
70
+ def build(
71
+ cls: type[Self],
72
+ *,
73
+ K: jtp.FloatLike = 1e6,
74
+ D: jtp.FloatLike = 2_000,
75
+ mu: jtp.FloatLike = 0.5,
76
+ p: jtp.FloatLike = 0.5,
77
+ q: jtp.FloatLike = 0.5,
78
+ **kwargs,
79
+ ) -> Self:
80
+ """
81
+ Create a SoftContactsParams instance with specified parameters.
82
+
83
+ Args:
84
+ K: The stiffness parameter.
85
+ D: The damping parameter of the soft contacts model.
86
+ mu: The static friction coefficient.
87
+ p:
88
+ The exponent p corresponding to the damping-related non-linearity
89
+ of the Hunt/Crossley model.
90
+ q:
91
+ The exponent q corresponding to the spring-related non-linearity
92
+ of the Hunt/Crossley model
93
+ **kwargs: Additional parameters to pass to the contact model.
94
+
95
+ Returns:
96
+ A SoftContactsParams instance with the specified parameters.
97
+ """
98
+
99
+ return SoftContactsParams(
100
+ K=jnp.array(K, dtype=float),
101
+ D=jnp.array(D, dtype=float),
102
+ mu=jnp.array(mu, dtype=float),
103
+ p=jnp.array(p, dtype=float),
104
+ q=jnp.array(q, dtype=float),
105
+ )
106
+
107
+ def valid(self) -> jtp.BoolLike:
108
+ """
109
+ Check if the parameters are valid.
110
+
111
+ Returns:
112
+ `True` if the parameters are valid, `False` otherwise.
113
+ """
114
+
115
+ return jnp.hstack(
116
+ [
117
+ self.K >= 0.0,
118
+ self.D >= 0.0,
119
+ self.mu >= 0.0,
120
+ self.p >= 0.0,
121
+ self.q >= 0.0,
122
+ ]
123
+ ).all()
124
+
125
+
126
+ @jax_dataclasses.pytree_dataclass
127
+ class SoftContacts(common.ContactModel):
128
+ """Soft contacts model."""
129
+
130
+ @classmethod
131
+ def build(
132
+ cls: type[Self],
133
+ model: js.model.JaxSimModel | None = None,
134
+ **kwargs,
135
+ ) -> Self:
136
+ """
137
+ Create a `SoftContacts` instance with specified parameters.
138
+
139
+ Args:
140
+ model:
141
+ The robot model considered by the contact model.
142
+ If passed, it is used to estimate good default parameters.
143
+ **kwargs: Additional parameters to pass to the contact model.
144
+
145
+ Returns:
146
+ The `SoftContacts` instance.
147
+ """
148
+
149
+ if len(kwargs) != 0:
150
+ logging.debug(msg=f"Ignoring extra arguments: {kwargs}")
151
+
152
+ return cls(**kwargs)
153
+
154
+ @classmethod
155
+ def zero_state_variables(cls, model: js.model.JaxSimModel) -> dict[str, jtp.Array]:
156
+ """
157
+ Build zero state variables of the contact model.
158
+ """
159
+
160
+ # Initialize the material deformation to zero.
161
+ tangential_deformation = jnp.zeros(
162
+ shape=(len(model.kin_dyn_parameters.contact_parameters.body), 3),
163
+ dtype=float,
164
+ )
165
+
166
+ return {"tangential_deformation": tangential_deformation}
167
+
168
+ def update_contact_state(
169
+ self: type[Self], old_contact_state: dict[str, jtp.Array]
170
+ ) -> dict[str, jtp.Array]:
171
+ """
172
+ Update the contact state.
173
+
174
+ Args:
175
+ old_contact_state: The old contact state.
176
+
177
+ Returns:
178
+ The updated contact state.
179
+ """
180
+
181
+ return {"tangential_deformation": old_contact_state["m_dot"]}
182
+
183
+ def update_velocity_after_impact(
184
+ self: type[Self], model: js.model.JaxSimModel, data: js.data.JaxSimModelData
185
+ ) -> js.data.JaxSimModelData:
186
+ """
187
+ Update the velocity after an impact.
188
+
189
+ Args:
190
+ model: The robot model considered by the contact model.
191
+ data: The data of the considered model.
192
+
193
+ Returns:
194
+ The updated data of the considered model.
195
+ """
196
+
197
+ return data
198
+
199
+ @staticmethod
200
+ @functools.partial(jax.jit, static_argnames=("terrain",))
201
+ def hunt_crossley_contact_model(
202
+ position: jtp.VectorLike,
203
+ velocity: jtp.VectorLike,
204
+ tangential_deformation: jtp.VectorLike,
205
+ terrain: Terrain,
206
+ K: jtp.FloatLike,
207
+ D: jtp.FloatLike,
208
+ mu: jtp.FloatLike,
209
+ p: jtp.FloatLike = 0.5,
210
+ q: jtp.FloatLike = 0.5,
211
+ ) -> tuple[jtp.Vector, jtp.Vector]:
212
+ """
213
+ Compute the contact force using the Hunt/Crossley model.
214
+
215
+ Args:
216
+ position: The position of the collidable point.
217
+ velocity: The velocity of the collidable point.
218
+ tangential_deformation: The material deformation of the collidable point.
219
+ terrain: The terrain model.
220
+ K: The stiffness parameter.
221
+ D: The damping parameter of the soft contacts model.
222
+ mu: The static friction coefficient.
223
+ p:
224
+ The exponent p corresponding to the damping-related non-linearity
225
+ of the Hunt/Crossley model.
226
+ q:
227
+ The exponent q corresponding to the spring-related non-linearity
228
+ of the Hunt/Crossley model
229
+
230
+ Returns:
231
+ A tuple containing the computed contact force and the derivative of the
232
+ material deformation.
233
+ """
234
+
235
+ # Convert the input vectors to arrays.
236
+ W_p_C = jnp.array(position, dtype=float).squeeze()
237
+ W_ṗ_C = jnp.array(velocity, dtype=float).squeeze()
238
+ m = jnp.array(tangential_deformation, dtype=float).squeeze()
239
+
240
+ # Use symbol for the static friction.
241
+ μ = mu
242
+
243
+ # Compute the penetration depth, its rate, and the considered terrain normal.
244
+ δ, δ̇, n̂ = common.compute_penetration_data(p=W_p_C, v=W_ṗ_C, terrain=terrain)
245
+
246
+ # There are few operations like computing the norm of a vector with zero length
247
+ # or computing the square root of zero that are problematic in an AD context.
248
+ # To avoid these issues, we introduce a small tolerance ε to their arguments
249
+ # and make sure that we do not check them against zero directly.
250
+ ε = jnp.finfo(float).eps
251
+
252
+ # Compute the powers of the penetration depth.
253
+ # Inject ε to address AD issues in differentiating the square root when
254
+ # p and q are fractional.
255
+ δp = jnp.power(δ + ε, p)
256
+ δq = jnp.power(δ + ε, q)
257
+
258
+ # ========================
259
+ # Compute the normal force
260
+ # ========================
261
+
262
+ # Non-linear spring-damper model (Hunt/Crossley model).
263
+ # This is the force magnitude along the direction normal to the terrain.
264
+ force_normal_mag = (K * δp) * δ + (D * δq) * δ̇
265
+
266
+ # Depending on the magnitude of δ̇, the normal force could be negative.
267
+ force_normal_mag = jnp.maximum(0.0, force_normal_mag)
268
+
269
+ # Compute the 3D linear force in C[W] frame.
270
+ f_normal = force_normal_mag * n̂
271
+
272
+ # ============================
273
+ # Compute the tangential force
274
+ # ============================
275
+
276
+ # Extract the tangential component of the velocity.
277
+ v_tangential = W_ṗ_C - jnp.dot(W_ṗ_C, n̂) * n̂
278
+
279
+ # Extract the normal and tangential components of the material deformation.
280
+ m_normal = jnp.dot(m, n̂) * n̂
281
+ m_tangential = m - jnp.dot(m, n̂) * n̂
282
+
283
+ # Compute the tangential force in the sticking case.
284
+ # Using the tangential component of the material deformation should not be
285
+ # necessary if the sticking-slipping transition occurs in a terrain area
286
+ # with a locally constant normal. However, this assumption is not true in
287
+ # general, especially for highly uneven terrains.
288
+ f_tangential = -((K * δp) * m_tangential + (D * δq) * v_tangential)
289
+
290
+ # Detect the contact type (sticking or slipping).
291
+ # Note that if there is no contact, sticking is set to True, and this detail
292
+ # is exploited in the computation of the `contact_status` variable.
293
+ sticking = jnp.logical_or(
294
+ δ <= 0, f_tangential.dot(f_tangential) <= (μ * force_normal_mag) ** 2
295
+ )
296
+
297
+ # Compute the direction of the tangential force.
298
+ # To prevent dividing by zero, we use a switch statement.
299
+ norm = jaxsim.math.safe_norm(f_tangential)
300
+ f_tangential_direction = f_tangential / (
301
+ norm + jnp.finfo(float).eps * (norm == 0)
302
+ )
303
+
304
+ # Project the tangential force to the friction cone if slipping.
305
+ f_tangential = jnp.where(
306
+ sticking,
307
+ f_tangential,
308
+ jnp.minimum(μ * force_normal_mag, norm) * f_tangential_direction,
309
+ )
310
+
311
+ # Set the tangential force to zero if there is no contact.
312
+ f_tangential = jnp.where(δ <= 0, jnp.zeros(3), f_tangential)
313
+
314
+ # =====================================
315
+ # Compute the material deformation rate
316
+ # =====================================
317
+
318
+ # Compute the derivative of the material deformation.
319
+ # Note that we included an additional relaxation of `m_normal` in the
320
+ # sticking case, so that the normal deformation that could have accumulated
321
+ # from a previous slipping phase can relax to zero.
322
+ ṁ_no_contact = -(K / D) * m
323
+ ṁ_sticking = v_tangential - (K / D) * m_normal
324
+ ṁ_slipping = -(f_tangential + (K * δp) * m_tangential) / (D * δq)
325
+
326
+ # Compute the contact status:
327
+ # 0: slipping
328
+ # 1: sticking
329
+ # 2: no contact
330
+ contact_status = sticking.astype(int)
331
+ contact_status += (δ <= 0).astype(int)
332
+
333
+ # Select the right material deformation rate depending on the contact status.
334
+ ṁ = jax.lax.select_n(contact_status, ṁ_slipping, ṁ_sticking, ṁ_no_contact)
335
+
336
+ # ==========================================
337
+ # Compute and return the final contact force
338
+ # ==========================================
339
+
340
+ # Sum the normal and tangential forces.
341
+ CW_fl = f_normal + f_tangential
342
+
343
+ return CW_fl, ṁ
344
+
345
+ @staticmethod
346
+ @functools.partial(jax.jit, static_argnames=("terrain",))
347
+ def compute_contact_force(
348
+ position: jtp.VectorLike,
349
+ velocity: jtp.VectorLike,
350
+ tangential_deformation: jtp.VectorLike,
351
+ parameters: SoftContactsParams,
352
+ terrain: Terrain,
353
+ ) -> tuple[jtp.Vector, jtp.Vector]:
354
+ """
355
+ Compute the contact force.
356
+
357
+ Args:
358
+ position: The position of the collidable point.
359
+ velocity: The velocity of the collidable point.
360
+ tangential_deformation: The material deformation of the collidable point.
361
+ parameters: The parameters of the soft contacts model.
362
+ terrain: The terrain model.
363
+
364
+ Returns:
365
+ A tuple containing the computed contact force and the derivative of the
366
+ material deformation.
367
+ """
368
+
369
+ CW_fl, ṁ = SoftContacts.hunt_crossley_contact_model(
370
+ position=position,
371
+ velocity=velocity,
372
+ tangential_deformation=tangential_deformation,
373
+ terrain=terrain,
374
+ K=parameters.K,
375
+ D=parameters.D,
376
+ mu=parameters.mu,
377
+ p=parameters.p,
378
+ q=parameters.q,
379
+ )
380
+
381
+ # Pack a mixed 6D force.
382
+ CW_f = jnp.hstack([CW_fl, jnp.zeros(3)])
383
+
384
+ # Compute the 6D force transform from the mixed to the inertial-fixed frame.
385
+ W_Xf_CW = jaxsim.math.Adjoint.from_quaternion_and_translation(
386
+ translation=jnp.array(position), inverse=True
387
+ ).T
388
+
389
+ # Compute the 6D force in the inertial-fixed frame.
390
+ W_f = W_Xf_CW @ CW_f
391
+
392
+ return W_f, ṁ
393
+
394
+ @staticmethod
395
+ @jax.jit
396
+ def compute_contact_forces(
397
+ model: js.model.JaxSimModel,
398
+ data: js.data.JaxSimModelData,
399
+ ) -> tuple[jtp.Matrix, dict[str, jtp.PyTree]]:
400
+ """
401
+ Compute the contact forces.
402
+
403
+ Args:
404
+ model: The model to consider.
405
+ data: The data of the considered model.
406
+
407
+ Returns:
408
+ A tuple containing as first element the computed contact forces, and as
409
+ second element a dictionary with derivative of the material deformation.
410
+ """
411
+
412
+ # Get the indices of the enabled collidable points.
413
+ indices_of_enabled_collidable_points = (
414
+ model.kin_dyn_parameters.contact_parameters.indices_of_enabled_collidable_points
415
+ )
416
+
417
+ # Compute the position and linear velocities (mixed representation) of
418
+ # all the collidable points belonging to the robot and extract the ones
419
+ # for the enabled collidable points.
420
+ W_p_C, W_ṗ_C = js.contact.collidable_point_kinematics(model=model, data=data)
421
+
422
+ # Extract the material deformation corresponding to the collidable points.
423
+ m = (
424
+ data.contact_state["tangential_deformation"]
425
+ if "tangential_deformation" in data.contact_state
426
+ else jnp.zeros_like(W_p_C)
427
+ )
428
+
429
+ m_enabled = m[indices_of_enabled_collidable_points]
430
+
431
+ # Initialize the tangential deformation rate array for every collidable point.
432
+ ṁ = jnp.zeros_like(m)
433
+
434
+ # Compute the contact forces only for the enabled collidable points.
435
+ # Since we treat them as independent, we can vmap the computation.
436
+ W_f, ṁ_enabled = jax.vmap(
437
+ lambda p, v, m: SoftContacts.compute_contact_force(
438
+ position=p,
439
+ velocity=v,
440
+ tangential_deformation=m,
441
+ parameters=model.contact_params,
442
+ terrain=model.terrain,
443
+ )
444
+ )(W_p_C, W_ṗ_C, m_enabled)
445
+
446
+ ṁ = ṁ.at[indices_of_enabled_collidable_points].set(ṁ_enabled)
447
+
448
+ return W_f, {"m_dot": ṁ}
@@ -111,32 +111,3 @@ def forward_kinematics_model(
111
111
  )
112
112
 
113
113
  return jax.vmap(Adjoint.to_transform)(W_X_i), W_v_Wi
114
-
115
-
116
- def forward_kinematics(
117
- model: js.model.JaxSimModel,
118
- link_index: jtp.Int,
119
- base_position: jtp.VectorLike,
120
- base_quaternion: jtp.VectorLike,
121
- joint_positions: jtp.VectorLike,
122
- ) -> jtp.Matrix:
123
- """
124
- Compute the forward kinematics of a specific link.
125
-
126
- Args:
127
- model: The model to consider.
128
- link_index: The index of the link to consider.
129
- base_position: The position of the base link.
130
- base_quaternion: The quaternion of the base link.
131
- joint_positions: The positions of the joints.
132
-
133
- Returns:
134
- The SE(3) transform of the link.
135
- """
136
-
137
- return forward_kinematics_model(
138
- model=model,
139
- base_position=base_position,
140
- base_quaternion=base_quaternion,
141
- joint_positions=joint_positions,
142
- )[link_index]
jaxsim/rbda/utils.py CHANGED
@@ -132,10 +132,10 @@ def process_inputs(
132
132
  if W_Q_B.shape != (4,):
133
133
  raise ValueError(W_Q_B.shape, (4,))
134
134
 
135
- # Check that the quaternion does not contain NaNs.
135
+ # Check that the quaternion does not contain NaN values.
136
136
  exceptions.raise_value_error_if(
137
137
  condition=jnp.isnan(W_Q_B).any(),
138
- msg="A RBDA received a quaternion that contains NaNs.",
138
+ msg="A RBDA received a quaternion that contains NaN values.",
139
139
  )
140
140
 
141
141
  # Check that the quaternion is unary since our RBDAs make this assumption in order
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
- Metadata-Version: 2.2
1
+ Metadata-Version: 2.4
2
2
  Name: jaxsim
3
- Version: 0.6.2.dev182
3
+ Version: 0.6.2.dev225
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>
@@ -89,6 +89,7 @@ Requires-Dist: mujoco>=3.0.0; extra == "viz"
89
89
  Requires-Dist: scipy>=1.14.0; extra == "viz"
90
90
  Provides-Extra: all
91
91
  Requires-Dist: jaxsim[style,testing,viz]; extra == "all"
92
+ Dynamic: license-file
92
93
 
93
94
  # JaxSim
94
95
 
@@ -1,41 +1,40 @@
1
1
  jaxsim/__init__.py,sha256=b8dYoVXqtHxHcF56iM2xgKk78lsvmGrfDlvdwaGasgs,3388
2
- jaxsim/_version.py,sha256=9vVqCpGd377pxkCsNsYmE64xHn05XG7hf09NdgSZsOA,528
2
+ jaxsim/_version.py,sha256=SLeXvaiJ6DysB1Pv4cxctaKKJ8fxxCYci0LspPXX0Q0,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
- jaxsim/api/__init__.py,sha256=Yck5Cr6_6yqGKwt2KicccEiy-hzIAOFA3G0sPXWQTgg,253
6
+ jaxsim/api/__init__.py,sha256=4skzcTTejLFfZ_JE6yEEyNxObpXnR5u-bYsn2lBEx-4,234
7
7
  jaxsim/api/actuation_model.py,sha256=L8AzxIiEquWeG8UGGJaYr2Alt4dkkOROlbsCn9hUYik,2825
8
- jaxsim/api/com.py,sha256=jhWcUsJtZYEQf-hnEvVuqH1KoiakBNLnTkj3PA6Cn-Q,13748
9
- jaxsim/api/common.py,sha256=jd3thxFUxcyoAMV3ZDMqfk2DlBdvWMZuI25Y0Pw5Dlo,7088
10
- jaxsim/api/contact.py,sha256=PpVtlb7Iw4mW0dCrGWorznzF2ai13N9SlV7DL5ecUfA,16795
11
- jaxsim/api/contact_model.py,sha256=gY7dRA6UIduD4OO1nRZ4VmnNXIOeDLulw5Am9gBjhUs,3334
12
- jaxsim/api/data.py,sha256=vfgzPBCbX9OUiCBKvyib2aevhZpH-MzU4ZNZsnhidQo,20790
8
+ jaxsim/api/com.py,sha256=47a9SSaXY540RCkVnHodwLNUrodIfJIkguIYdSEQVwQ,13697
9
+ jaxsim/api/common.py,sha256=yTaRXDYkXmISBOhZ93f9TssR0p4wq7qj7B6OsvYzRME,6942
10
+ jaxsim/api/contact.py,sha256=dlKKDQUG-KQ5qQaYBv2NmZLDb1OnJdltZv8MWXkD_W0,20969
11
+ jaxsim/api/data.py,sha256=aW6buyH3YszzEBqBXqBgHf6uaSilZcqU7PyP60qgLco,23336
13
12
  jaxsim/api/frame.py,sha256=4wg6GsyBQgYhSvc-ry_31JsaL66sZt3TtgwjB7NrHmk,14583
14
- jaxsim/api/integrators.py,sha256=O2WmwW-3lZEiA2Pp0-CsyYlnoqaz0zqqNdeCZUI5O6Q,4980
13
+ jaxsim/api/integrators.py,sha256=DgOnzLepy45e-TM6Infk8qfPXn0r8GubCdJQZmNLP8w,5269
15
14
  jaxsim/api/joint.py,sha256=AnqlNWmBOay-gsoo0y4AbfFQ2OCJm-8T1E0IMhZeLoY,7457
16
15
  jaxsim/api/kin_dyn_parameters.py,sha256=v1ZDb-Eqn552Zb344sJYy9e5sQT--_SYGIdtNC2JVSg,29828
17
16
  jaxsim/api/link.py,sha256=bSZOYJDY9HJMgY25VzevTTsdFZTJc6yRRpslc5FhGHE,12782
18
- jaxsim/api/model.py,sha256=czjv_OcjIYjCzN-LHv2qSSrAkPSPcsLCEe_kD6XZnuA,69846
19
- jaxsim/api/ode.py,sha256=rGOswAcchEdzx8ZfMDTR2F6AjkHymZgTTdvBbjPPpd4,5358
20
- jaxsim/api/references.py,sha256=ywNiURwZ0niYB-AzX1eoWCfdrx7TBiRyyfi_2tz-ako,20677
21
- jaxsim/math/__init__.py,sha256=lWMswEnITzQ69O761CiHL-r7UrxyIqsHlk4YTNxtwAY,384
22
- jaxsim/math/adjoint.py,sha256=mAtCwddK1ZwpVgIp4GIY8EVAW32Z67AJl_BzREf0ih8,4731
17
+ jaxsim/api/model.py,sha256=LkhQaN4ZgoQUOTTtDaa4y689vTF14VCeVeaqCkjB_t8,69237
18
+ jaxsim/api/ode.py,sha256=fp20_LK9lXw2DfNkQgrfJmtd_iBXDNzZkOn0u5Pm8Qw,6190
19
+ jaxsim/api/references.py,sha256=-vd50y3v-jkXAsILS432etIKV6e2EUE2oOeLHuUrfuQ,20399
20
+ jaxsim/math/__init__.py,sha256=dNozvtm8WsB7nxw4uK29yQQKPcDUEczr2zcHoZfMItc,383
21
+ jaxsim/math/adjoint.py,sha256=Pb0WAiAoN1ge8j_dPcdK307jmC5LzD1-DeUj9Z_NXkI,4667
23
22
  jaxsim/math/cross.py,sha256=AM4HauuuT09q2TN42qvdXhJ9LvtCh0e7ZyLjP-7sANs,1498
24
23
  jaxsim/math/inertia.py,sha256=T-iAjPYSD_72R0ZG8GDJhe5i3Jc3ojhlbBRSscTdCKg,1577
25
24
  jaxsim/math/joint_model.py,sha256=mV6F3SVHUxHcXMIw-hc4fG341R4rkK8MvRPn53HcEpg,6915
26
25
  jaxsim/math/quaternion.py,sha256=MSaZywzJDxs2te1ZELeIcupKSFIA9q_pdXy7fDAEqM4,4539
27
26
  jaxsim/math/rotation.py,sha256=TEUtT3X2tFieNxdlccup1pfaTgCTtfX-hTNotd8-nNk,1892
28
27
  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
28
+ jaxsim/math/transform.py,sha256=NOWBQgL_5hVr9aHA7j0Ta-Zq_EXAKguUAx78fVPZJE4,3342
29
+ jaxsim/math/utils.py,sha256=IiH01iN54BtLnULC04pDfYe8Av99p3FGdYp2jJInm30,1166
31
30
  jaxsim/mujoco/__init__.py,sha256=1kAWzYOS7nP29S5FGyWPqiAnPf4yPSoaPW-WBGBjVV0,214
32
31
  jaxsim/mujoco/__main__.py,sha256=GBmB7J-zj75ZnFyuAAmpSOpbxi_HhHhWJeot3ljGDJY,5291
33
32
  jaxsim/mujoco/loaders.py,sha256=OCk1T11iIm3qZUibNpo_bxxLgaGSkCpLt7ae_ND0ExA,23272
34
33
  jaxsim/mujoco/model.py,sha256=bRXo1uhWDN37sP9qdejr_2vq_PXHQ7p6eyBlFff_JcE,16492
35
34
  jaxsim/mujoco/utils.py,sha256=dW3LrcM050-eVVdLuCiN3StIrTEfyk_jJyq1GiNh3fg,8396
36
- jaxsim/mujoco/visualizer.py,sha256=7CYxxqPZdCp9Wc77ZGe1t8Z_SIgBpoJAtYcvQMcCJvQ,7746
35
+ jaxsim/mujoco/visualizer.py,sha256=cmI6DhFb1XC7oEtg_wl-s-U56dWHA-F7GlBD6EDYTyA,7744
37
36
  jaxsim/parsers/__init__.py,sha256=47DEQpj8HBSa-_TImW-5JCeuQeRkm5NMpJWZG3hSuFU,0
38
- jaxsim/parsers/kinematic_graph.py,sha256=YkxnykmGIXYs5fSXUX1mIi81mm7lG4HMt8LyRV-31j0,35759
37
+ jaxsim/parsers/kinematic_graph.py,sha256=s6sKPOGj_St4dfooNhE5a4F4tO3qTODErLYx8dfZRJk,35757
39
38
  jaxsim/parsers/descriptions/__init__.py,sha256=N_hp8cGI5FyEFiuNx9a-CAGCr0F0QpYEpdMHvwB7_1g,261
40
39
  jaxsim/parsers/descriptions/collision.py,sha256=C6SekAPL2tNG62Y-lTqj1m9BblhoTZDj2F2vgspKNbI,4577
41
40
  jaxsim/parsers/descriptions/joint.py,sha256=MurLIHHmu-y_bwUcR_J1NZ-FjfRZRk166zKsn6VzIwE,4232
@@ -45,25 +44,27 @@ jaxsim/parsers/rod/__init__.py,sha256=G2vqlLajBLUc4gyzXwsEI2Wsi4TMOIF9bLDFeT6KrG
45
44
  jaxsim/parsers/rod/meshes.py,sha256=yAXefG73_zqbVKRUdlcz9yFmypjDIpiP9cO96PeAozE,2842
46
45
  jaxsim/parsers/rod/parser.py,sha256=vaOlvlvgQCEGbymFc21praHKEVq_LqqlKeRJNv7tZiE,14398
47
46
  jaxsim/parsers/rod/utils.py,sha256=wmD-wCF1lLO8pknX7A3a8CGt9wDlTS_xCqQulcZ_XlM,8242
48
- jaxsim/rbda/__init__.py,sha256=kmy4G9aMkrqPNGdLSaSV3k15dpF52vBEUQXDFDuKIxU,337
47
+ jaxsim/rbda/__init__.py,sha256=nQ01ALTXm8lJAb5flCOzxfjyDZPbDrP4H3v-xlfyCss,317
49
48
  jaxsim/rbda/aba.py,sha256=QiajR4Uv06u-BX5V2kWpmFmP_kIfTxxcycdJhIbid9A,9029
50
49
  jaxsim/rbda/collidable_points.py,sha256=XyeV1I43GL22j03rkNVocaIPOGYirt3PiDHrFMndziQ,2070
51
50
  jaxsim/rbda/crba.py,sha256=DC9kBXMG1qXaoAdo8K7OCnVHT_YUaL_t6Li56sRf8ro,5093
52
- jaxsim/rbda/forward_kinematics.py,sha256=zoyXEZnL-hyJr3c9Jl0EfCleJtVvVsekHgUTLn5EiQ4,4640
51
+ jaxsim/rbda/forward_kinematics.py,sha256=qem7Yp-B2oNVOsU3Q2CWV2tbfZKJOCAdDozFgaPB8tg,3838
53
52
  jaxsim/rbda/jacobian.py,sha256=EaMvf073UnLWJGXm4UZIlYd4erulFAGgj_pp89k6xic,11113
54
53
  jaxsim/rbda/rnea.py,sha256=lMU7xxdPqGGzk0QwteB-IYjL4auHOpd78C1YqAXlp9s,7588
55
- jaxsim/rbda/utils.py,sha256=LDm00VhNjH2STo5y48PAtO4TC75Bybi60-Viuq3Cyss,5575
56
- jaxsim/rbda/contacts/__init__.py,sha256=eZKSoGpWH6IQIofhXzU-q9J00PkKTovPVnxubmzoK0E,202
57
- jaxsim/rbda/contacts/common.py,sha256=QSvEykjN5MuRD7Vk-rM454qBYdkwH7xZAVOBeulKAUc,5042
58
- jaxsim/rbda/contacts/relaxed_rigid.py,sha256=BTHOr0An_6K3UIkGYakaF05gkTsKHDSinDzirlvSY8o,26742
54
+ jaxsim/rbda/utils.py,sha256=6JwEDQqLMsBX7CUmPYEhdPEscXmGbWVYg6xEriPOgvE,5587
55
+ jaxsim/rbda/contacts/__init__.py,sha256=resrBkTdOA-1YMdcdUH2RATEhAf_Ye6MQNtjG3ClMYQ,371
56
+ jaxsim/rbda/contacts/common.py,sha256=qVm3Ghoytg1HAeykNrYw5-4rQJ4Mv7h0Pk75ETzGXyc,9045
57
+ jaxsim/rbda/contacts/relaxed_rigid.py,sha256=QlRcFDscGo2Z2M33Gqb5LnYHGTSdGONoU-kqS2J5qkM,21151
58
+ jaxsim/rbda/contacts/rigid.py,sha256=zlPXYwNf4HlJlp4t-X_dA5n1Ys-fhLiAQ-gM29fXnYo,17583
59
+ jaxsim/rbda/contacts/soft.py,sha256=Ac9aWDdjAm55Mv9LLnEs3nj7hX_NvJMnicV35SbFLSY,15282
59
60
  jaxsim/terrain/__init__.py,sha256=f7lVX-iNpH_wkkjef9Qpjh19TTAUOQw76EiLYJDVizc,78
60
- jaxsim/terrain/terrain.py,sha256=TH84r2qizMmsfW7zYLViRjacCfOkqdYHsCzD1lZEY4c,6716
61
+ jaxsim/terrain/terrain.py,sha256=so8kqVsUlPXqOKQ_UaYW6HE4XS8nTZRdFdXQyhB2tG4,6725
61
62
  jaxsim/utils/__init__.py,sha256=Y5zyoRevl3EMVQadhZ4EtSwTEkDt2vcnFoRhPJjKTZ0,215
62
63
  jaxsim/utils/jaxsim_dataclass.py,sha256=XzmZeIibcaOzaxpprsGSxH3UrM66PAO456rFV91sNXg,11453
63
64
  jaxsim/utils/tracing.py,sha256=Btwxdfhb7fJLk3r5PlQkGYj60Y2KbFT1gANGIA697FU,530
64
65
  jaxsim/utils/wrappers.py,sha256=3IMwydqFgmSPqeuUQ3PRmdhDc1IoT6XC23jPC_LjWXs,4175
65
- jaxsim-0.6.2.dev182.dist-info/LICENSE,sha256=eaYdFmdeMbiIoIiPzEK0MjP1S9wtFXjXNR5er49uLR0,1546
66
- jaxsim-0.6.2.dev182.dist-info/METADATA,sha256=jAiUH_e3tQd-cYMXURWWZFlvlLw-m2lCYOiYk1zNLlg,19991
67
- jaxsim-0.6.2.dev182.dist-info/WHEEL,sha256=beeZ86-EfXScwlR_HKu4SllMC9wUEj_8Z_4FJ3egI2w,91
68
- jaxsim-0.6.2.dev182.dist-info/top_level.txt,sha256=LxGMA8FLtXjQ6oI7N5gd_R_oSUHxpXxUEOfT1xS_ni0,7
69
- jaxsim-0.6.2.dev182.dist-info/RECORD,,
66
+ jaxsim-0.6.2.dev225.dist-info/licenses/LICENSE,sha256=eaYdFmdeMbiIoIiPzEK0MjP1S9wtFXjXNR5er49uLR0,1546
67
+ jaxsim-0.6.2.dev225.dist-info/METADATA,sha256=6jlXlKkNxnbIC0H6dwcdX1qBKVL0yDamRTW9SgcCzLY,20013
68
+ jaxsim-0.6.2.dev225.dist-info/WHEEL,sha256=tTnHoFhvKQHCh4jz3yCn0WPTYIy7wXx3CJtJ7SJGV7c,91
69
+ jaxsim-0.6.2.dev225.dist-info/top_level.txt,sha256=LxGMA8FLtXjQ6oI7N5gd_R_oSUHxpXxUEOfT1xS_ni0,7
70
+ jaxsim-0.6.2.dev225.dist-info/RECORD,,
@@ -1,5 +1,5 @@
1
1
  Wheel-Version: 1.0
2
- Generator: setuptools (76.1.0)
2
+ Generator: setuptools (77.0.1)
3
3
  Root-Is-Purelib: true
4
4
  Tag: py3-none-any
5
5