jaxsim 0.2.1.dev115__py3-none-any.whl → 0.2.1.dev121__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 +2 -2
- jaxsim/api/link.py +182 -0
- jaxsim/rbda/__init__.py +5 -1
- jaxsim/rbda/jacobian.py +118 -1
- {jaxsim-0.2.1.dev115.dist-info → jaxsim-0.2.1.dev121.dist-info}/METADATA +1 -1
- {jaxsim-0.2.1.dev115.dist-info → jaxsim-0.2.1.dev121.dist-info}/RECORD +9 -9
- {jaxsim-0.2.1.dev115.dist-info → jaxsim-0.2.1.dev121.dist-info}/LICENSE +0 -0
- {jaxsim-0.2.1.dev115.dist-info → jaxsim-0.2.1.dev121.dist-info}/WHEEL +0 -0
- {jaxsim-0.2.1.dev115.dist-info → jaxsim-0.2.1.dev121.dist-info}/top_level.txt +0 -0
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.1.
|
16
|
-
__version_tuple__ = version_tuple = (0, 2, 1, '
|
15
|
+
__version__ = version = '0.2.1.dev121'
|
16
|
+
__version_tuple__ = version_tuple = (0, 2, 1, 'dev121')
|
jaxsim/api/link.py
CHANGED
@@ -3,6 +3,7 @@ from typing import Sequence
|
|
3
3
|
|
4
4
|
import jax
|
5
5
|
import jax.numpy as jnp
|
6
|
+
import jax.scipy.linalg
|
6
7
|
import jaxlie
|
7
8
|
import numpy as np
|
8
9
|
|
@@ -337,6 +338,187 @@ def velocity(
|
|
337
338
|
return O_J_WL_I @ I_ν
|
338
339
|
|
339
340
|
|
341
|
+
@functools.partial(jax.jit, static_argnames=["output_vel_repr"])
|
342
|
+
def jacobian_derivative(
|
343
|
+
model: js.model.JaxSimModel,
|
344
|
+
data: js.data.JaxSimModelData,
|
345
|
+
*,
|
346
|
+
link_index: jtp.IntLike,
|
347
|
+
output_vel_repr: VelRepr | None = None,
|
348
|
+
) -> jtp.Matrix:
|
349
|
+
"""
|
350
|
+
Compute the derivative of the free-floating jacobian of the link.
|
351
|
+
|
352
|
+
Args:
|
353
|
+
model: The model to consider.
|
354
|
+
data: The data of the considered model.
|
355
|
+
link_index: The index of the link.
|
356
|
+
output_vel_repr:
|
357
|
+
The output velocity representation of the free-floating jacobian derivative.
|
358
|
+
|
359
|
+
Returns:
|
360
|
+
The derivative of the 6×(6+n) free-floating jacobian of the link.
|
361
|
+
|
362
|
+
Note:
|
363
|
+
The input representation of the free-floating jacobian derivative is the active
|
364
|
+
velocity representation.
|
365
|
+
"""
|
366
|
+
|
367
|
+
output_vel_repr = (
|
368
|
+
output_vel_repr if output_vel_repr is not None else data.velocity_representation
|
369
|
+
)
|
370
|
+
|
371
|
+
# Compute the derivative of the doubly-left free-floating full jacobian.
|
372
|
+
B_J̇_full_WX_B, B_H_L = jaxsim.rbda.jacobian_derivative_full_doubly_left(
|
373
|
+
model=model,
|
374
|
+
joint_positions=data.joint_positions(),
|
375
|
+
joint_velocities=data.joint_velocities(),
|
376
|
+
)
|
377
|
+
|
378
|
+
# Compute the actual doubly-left free-floating jacobian derivative of the link
|
379
|
+
# by zeroing the columns not in the path π_B(L) using the boolean κ(i).
|
380
|
+
κb = model.kin_dyn_parameters.support_body_array_bool[link_index]
|
381
|
+
B_J̇_WL_B = jnp.hstack([jnp.ones(5), κb]) * B_J̇_full_WX_B
|
382
|
+
|
383
|
+
# =====================================================
|
384
|
+
# Compute quantities to adjust the input representation
|
385
|
+
# =====================================================
|
386
|
+
|
387
|
+
In = jnp.eye(model.dofs())
|
388
|
+
On = jnp.zeros(shape=(model.dofs(), model.dofs()))
|
389
|
+
|
390
|
+
match data.velocity_representation:
|
391
|
+
|
392
|
+
case VelRepr.Inertial:
|
393
|
+
|
394
|
+
W_H_B = data.base_transform()
|
395
|
+
B_X_W = jaxsim.math.Adjoint.from_transform(transform=W_H_B, inverse=True)
|
396
|
+
|
397
|
+
with data.switch_velocity_representation(VelRepr.Inertial):
|
398
|
+
W_v_WB = data.base_velocity()
|
399
|
+
B_Ẋ_W = -B_X_W @ jaxsim.math.Cross.vx(W_v_WB)
|
400
|
+
|
401
|
+
# Compute the operator to change the representation of ν, and its
|
402
|
+
# time derivative.
|
403
|
+
T = jax.scipy.linalg.block_diag(B_X_W, In)
|
404
|
+
Ṫ = jax.scipy.linalg.block_diag(B_Ẋ_W, On)
|
405
|
+
|
406
|
+
case VelRepr.Body:
|
407
|
+
|
408
|
+
B_X_B = jaxsim.math.Adjoint.from_rotation_and_translation(
|
409
|
+
translation=jnp.zeros(3), rotation=jnp.eye(3)
|
410
|
+
)
|
411
|
+
|
412
|
+
B_Ẋ_B = jnp.zeros(shape=(6, 6))
|
413
|
+
|
414
|
+
# Compute the operator to change the representation of ν, and its
|
415
|
+
# time derivative.
|
416
|
+
T = jax.scipy.linalg.block_diag(B_X_B, In)
|
417
|
+
Ṫ = jax.scipy.linalg.block_diag(B_Ẋ_B, On)
|
418
|
+
|
419
|
+
case VelRepr.Mixed:
|
420
|
+
|
421
|
+
BW_H_B = data.base_transform().at[0:3, 3].set(jnp.zeros(3))
|
422
|
+
B_X_BW = jaxsim.math.Adjoint.from_transform(transform=BW_H_B, inverse=True)
|
423
|
+
|
424
|
+
with data.switch_velocity_representation(VelRepr.Mixed):
|
425
|
+
BW_v_WB = data.base_velocity()
|
426
|
+
BW_v_W_BW = BW_v_WB.at[3:6].set(jnp.zeros(3))
|
427
|
+
|
428
|
+
BW_v_BW_B = BW_v_WB - BW_v_W_BW
|
429
|
+
B_Ẋ_BW = -B_X_BW @ jaxsim.math.Cross.vx(BW_v_BW_B)
|
430
|
+
|
431
|
+
# Compute the operator to change the representation of ν, and its
|
432
|
+
# time derivative.
|
433
|
+
T = jax.scipy.linalg.block_diag(B_X_BW, In)
|
434
|
+
Ṫ = jax.scipy.linalg.block_diag(B_Ẋ_BW, On)
|
435
|
+
|
436
|
+
case _:
|
437
|
+
raise ValueError(data.velocity_representation)
|
438
|
+
|
439
|
+
# ======================================================
|
440
|
+
# Compute quantities to adjust the output representation
|
441
|
+
# ======================================================
|
442
|
+
|
443
|
+
match output_vel_repr:
|
444
|
+
|
445
|
+
case VelRepr.Inertial:
|
446
|
+
|
447
|
+
W_H_B = data.base_transform()
|
448
|
+
O_X_B = W_X_B = jaxsim.math.Adjoint.from_transform(transform=W_H_B)
|
449
|
+
|
450
|
+
with data.switch_velocity_representation(VelRepr.Body):
|
451
|
+
B_v_WB = data.base_velocity()
|
452
|
+
|
453
|
+
O_Ẋ_B = W_Ẋ_B = W_X_B @ jaxsim.math.Cross.vx(B_v_WB)
|
454
|
+
|
455
|
+
case VelRepr.Body:
|
456
|
+
|
457
|
+
O_X_B = L_X_B = jaxsim.math.Adjoint.from_transform(
|
458
|
+
transform=B_H_L[link_index, :, :], inverse=True
|
459
|
+
)
|
460
|
+
|
461
|
+
B_X_L = jaxsim.math.Adjoint.inverse(adjoint=L_X_B)
|
462
|
+
|
463
|
+
with data.switch_velocity_representation(VelRepr.Body):
|
464
|
+
B_v_WB = data.base_velocity()
|
465
|
+
L_v_WL = js.link.velocity(model=model, data=data, link_index=link_index)
|
466
|
+
|
467
|
+
O_Ẋ_B = L_Ẋ_B = -L_X_B @ jaxsim.math.Cross.vx(B_X_L @ L_v_WL - B_v_WB)
|
468
|
+
|
469
|
+
case VelRepr.Mixed:
|
470
|
+
|
471
|
+
W_H_B = data.base_transform()
|
472
|
+
W_H_L = W_H_B @ B_H_L[link_index, :, :]
|
473
|
+
LW_H_L = W_H_L.at[0:3, 3].set(jnp.zeros(3))
|
474
|
+
LW_H_B = LW_H_L @ jaxsim.math.Transform.inverse(B_H_L[link_index, :, :])
|
475
|
+
|
476
|
+
O_X_B = LW_X_B = jaxsim.math.Adjoint.from_transform(transform=LW_H_B)
|
477
|
+
|
478
|
+
B_X_LW = jaxsim.math.Adjoint.inverse(adjoint=LW_X_B)
|
479
|
+
|
480
|
+
with data.switch_velocity_representation(VelRepr.Body):
|
481
|
+
B_v_WB = data.base_velocity()
|
482
|
+
|
483
|
+
with data.switch_velocity_representation(VelRepr.Mixed):
|
484
|
+
LW_v_WL = js.link.velocity(
|
485
|
+
model=model, data=data, link_index=link_index
|
486
|
+
)
|
487
|
+
LW_v_W_LW = LW_v_WL.at[3:6].set(jnp.zeros(3))
|
488
|
+
|
489
|
+
LW_v_LW_L = LW_v_WL - LW_v_W_LW
|
490
|
+
LW_v_B_LW = LW_v_WL - LW_X_B @ B_v_WB - LW_v_LW_L
|
491
|
+
|
492
|
+
O_Ẋ_B = LW_Ẋ_B = -LW_X_B @ jaxsim.math.Cross.vx(B_X_LW @ LW_v_B_LW)
|
493
|
+
|
494
|
+
case _:
|
495
|
+
raise ValueError(output_vel_repr)
|
496
|
+
|
497
|
+
# =============================================================
|
498
|
+
# Express the Jacobian derivative in the target representations
|
499
|
+
# =============================================================
|
500
|
+
|
501
|
+
# The derivative of the equation to change the input and output representations
|
502
|
+
# of the Jacobian derivative needs the computation of the plain link Jacobian.
|
503
|
+
# Compute here the full Jacobian of the model...
|
504
|
+
B_J_full_WL_B, _ = jaxsim.rbda.jacobian_full_doubly_left(
|
505
|
+
model=model,
|
506
|
+
joint_positions=data.joint_positions(),
|
507
|
+
)
|
508
|
+
|
509
|
+
# ... and extract the link Jacobian using the boolean support body array.
|
510
|
+
B_J_WL_B = jnp.hstack([jnp.ones(5), κb]) * B_J_full_WL_B
|
511
|
+
|
512
|
+
# Sum all the components that form the Jacobian derivative in the target
|
513
|
+
# input/output velocity representations.
|
514
|
+
O_J̇_WL_I = jnp.zeros(shape=(6, 6 + model.dofs()))
|
515
|
+
O_J̇_WL_I += O_Ẋ_B @ B_J_WL_B @ T
|
516
|
+
O_J̇_WL_I += O_X_B @ B_J̇_WL_B @ T
|
517
|
+
O_J̇_WL_I += O_X_B @ B_J_WL_B @ Ṫ
|
518
|
+
|
519
|
+
return O_J̇_WL_I
|
520
|
+
|
521
|
+
|
340
522
|
@jax.jit
|
341
523
|
def bias_acceleration(
|
342
524
|
model: js.model.JaxSimModel,
|
jaxsim/rbda/__init__.py
CHANGED
@@ -2,6 +2,10 @@ from .aba import aba
|
|
2
2
|
from .collidable_points import collidable_points_pos_vel
|
3
3
|
from .crba import crba
|
4
4
|
from .forward_kinematics import forward_kinematics, forward_kinematics_model
|
5
|
-
from .jacobian import
|
5
|
+
from .jacobian import (
|
6
|
+
jacobian,
|
7
|
+
jacobian_derivative_full_doubly_left,
|
8
|
+
jacobian_full_doubly_left,
|
9
|
+
)
|
6
10
|
from .rnea import rnea
|
7
11
|
from .soft_contacts import SoftContacts, SoftContactsParams
|
jaxsim/rbda/jacobian.py
CHANGED
@@ -4,7 +4,7 @@ import numpy as np
|
|
4
4
|
|
5
5
|
import jaxsim.api as js
|
6
6
|
import jaxsim.typing as jtp
|
7
|
-
from jaxsim.math import Adjoint
|
7
|
+
from jaxsim.math import Adjoint, Cross
|
8
8
|
|
9
9
|
from . import utils
|
10
10
|
|
@@ -199,3 +199,120 @@ def jacobian_full_doubly_left(
|
|
199
199
|
B_J_full_WL_B = J.squeeze().astype(float)
|
200
200
|
|
201
201
|
return B_J_full_WL_B, B_H_L
|
202
|
+
|
203
|
+
|
204
|
+
def jacobian_derivative_full_doubly_left(
|
205
|
+
model: js.model.JaxSimModel,
|
206
|
+
*,
|
207
|
+
joint_positions: jtp.VectorLike,
|
208
|
+
joint_velocities: jtp.VectorLike,
|
209
|
+
) -> tuple[jtp.Matrix, jtp.Array]:
|
210
|
+
r"""
|
211
|
+
Compute the derivative of the doubly-left full free-floating Jacobian of a model.
|
212
|
+
|
213
|
+
The derivative of the full Jacobian is a 6x(6+n) matrix with all the columns filled.
|
214
|
+
It is useful to run the algorithm once, and then extract the link Jacobian
|
215
|
+
derivative by filtering the columns of the full Jacobian using the support
|
216
|
+
parent array :math:`\kappa(i)` of the link.
|
217
|
+
|
218
|
+
Args:
|
219
|
+
model: The model to consider.
|
220
|
+
joint_positions: The positions of the joints.
|
221
|
+
joint_velocities: The velocities of the joints.
|
222
|
+
|
223
|
+
Returns:
|
224
|
+
The derivative of the doubly-left full free-floating Jacobian of a model.
|
225
|
+
"""
|
226
|
+
|
227
|
+
_, _, s, _, ṡ, _, _, _, _, _ = utils.process_inputs(
|
228
|
+
model=model, joint_positions=joint_positions, joint_velocities=joint_velocities
|
229
|
+
)
|
230
|
+
|
231
|
+
# Get the parent array λ(i).
|
232
|
+
# Note: λ(0) must not be used, it's initialized to -1.
|
233
|
+
λ = model.kin_dyn_parameters.parent_array
|
234
|
+
|
235
|
+
# Compute the parent-to-child adjoints and the motion subspaces of the joints.
|
236
|
+
# These transforms define the relative kinematics of the entire model, including
|
237
|
+
# the base transform for both floating-base and fixed-base models.
|
238
|
+
i_X_λi, S = model.kin_dyn_parameters.joint_transforms_and_motion_subspaces(
|
239
|
+
joint_positions=s, base_transform=jnp.eye(4)
|
240
|
+
)
|
241
|
+
|
242
|
+
# Allocate the buffer of 6D transform base -> link.
|
243
|
+
B_X_i = jnp.zeros(shape=(model.number_of_links(), 6, 6))
|
244
|
+
B_X_i = B_X_i.at[0].set(jnp.eye(6))
|
245
|
+
|
246
|
+
# Allocate the buffer of 6D transform derivatives base -> link.
|
247
|
+
B_Ẋ_i = jnp.zeros(shape=(model.number_of_links(), 6, 6))
|
248
|
+
|
249
|
+
# Allocate the buffer of the 6D link velocity in body-fixed representation.
|
250
|
+
B_v_Bi = jnp.zeros(shape=(model.number_of_links(), 6))
|
251
|
+
|
252
|
+
# Helper to compute the time derivative of the adjoint matrix.
|
253
|
+
def A_Ẋ_B(A_X_B: jtp.Matrix, B_v_AB: jtp.Vector) -> jtp.Matrix:
|
254
|
+
return A_X_B @ Cross.vx(B_v_AB).squeeze()
|
255
|
+
|
256
|
+
# ============================================
|
257
|
+
# Compute doubly-left full Jacobian derivative
|
258
|
+
# ============================================
|
259
|
+
|
260
|
+
# Allocate the Jacobian matrix.
|
261
|
+
J̇ = jnp.zeros(shape=(6, 6 + model.dofs()))
|
262
|
+
|
263
|
+
ComputeFullJacobianDerivativeCarry = tuple[
|
264
|
+
jtp.MatrixJax, jtp.MatrixJax, jtp.MatrixJax, jtp.MatrixJax
|
265
|
+
]
|
266
|
+
|
267
|
+
compute_full_jacobian_derivative_carry: ComputeFullJacobianDerivativeCarry = (
|
268
|
+
B_v_Bi,
|
269
|
+
B_X_i,
|
270
|
+
B_Ẋ_i,
|
271
|
+
J̇,
|
272
|
+
)
|
273
|
+
|
274
|
+
def compute_full_jacobian_derivative(
|
275
|
+
carry: ComputeFullJacobianDerivativeCarry, i: jtp.Int
|
276
|
+
) -> tuple[ComputeFullJacobianDerivativeCarry, None]:
|
277
|
+
|
278
|
+
ii = i - 1
|
279
|
+
B_v_Bi, B_X_i, B_Ẋ_i, J̇ = carry
|
280
|
+
|
281
|
+
# Compute the base (0) to link (i) adjoint matrix.
|
282
|
+
B_Xi_i = B_X_i[λ[i]] @ Adjoint.inverse(i_X_λi[i])
|
283
|
+
B_X_i = B_X_i.at[i].set(B_Xi_i)
|
284
|
+
|
285
|
+
# Compute the body-fixed velocity of the link.
|
286
|
+
B_vi_Bi = B_v_Bi[λ[i]] + B_X_i[i] @ S[i].squeeze() * ṡ[ii]
|
287
|
+
B_v_Bi = B_v_Bi.at[i].set(B_vi_Bi)
|
288
|
+
|
289
|
+
# Compute the base (0) to link (i) adjoint matrix derivative.
|
290
|
+
i_Xi_B = Adjoint.inverse(B_Xi_i)
|
291
|
+
B_Ẋi_i = A_Ẋ_B(A_X_B=B_Xi_i, B_v_AB=i_Xi_B @ B_vi_Bi)
|
292
|
+
B_Ẋ_i = B_Ẋ_i.at[i].set(B_Ẋi_i)
|
293
|
+
|
294
|
+
# Compute the ii-th column of the B_Ṡ_BL(s) matrix.
|
295
|
+
B_Ṡii_BL = B_Ẋ_i[i] @ S[i]
|
296
|
+
J̇ = J̇.at[0:6, 6 + ii].set(B_Ṡii_BL.squeeze())
|
297
|
+
|
298
|
+
return (B_v_Bi, B_X_i, B_Ẋ_i, J̇), None
|
299
|
+
|
300
|
+
(_, B_X_i, B_Ẋ_i, J̇), _ = (
|
301
|
+
jax.lax.scan(
|
302
|
+
f=compute_full_jacobian_derivative,
|
303
|
+
init=compute_full_jacobian_derivative_carry,
|
304
|
+
xs=np.arange(start=1, stop=model.number_of_links()),
|
305
|
+
)
|
306
|
+
if model.number_of_links() > 1
|
307
|
+
else [(_, B_X_i, B_Ẋ_i, J̇), None]
|
308
|
+
)
|
309
|
+
|
310
|
+
# Convert adjoints to SE(3) transforms.
|
311
|
+
# Returning them here prevents calling FK in case the output representation
|
312
|
+
# of the Jacobian needs to be changed.
|
313
|
+
B_H_L = jax.vmap(lambda B_X_L: Adjoint.to_transform(B_X_L))(B_X_i)
|
314
|
+
|
315
|
+
# Adjust shape of doubly-left free-floating full Jacobian derivative.
|
316
|
+
B_J̇_full_WL_B = J̇.squeeze().astype(float)
|
317
|
+
|
318
|
+
return B_J̇_full_WL_B, B_H_L
|
@@ -1,5 +1,5 @@
|
|
1
1
|
jaxsim/__init__.py,sha256=OcrfoYS1DGcmAGqu2AqlCTiUVxcpi-IsVwcr_16x74Q,1789
|
2
|
-
jaxsim/_version.py,sha256=
|
2
|
+
jaxsim/_version.py,sha256=KFUBivTgY0a-4aSYOi6xZcqBRCxbrBngLa_iJrJtGQM,428
|
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=8eV22t2S3UwNyCg8karPetG1dmX1VDBXkyv28_FwNQA,210
|
@@ -10,7 +10,7 @@ jaxsim/api/data.py,sha256=xfKJz6Rw0YTk-EHCGiT8BFQrs_ggOz01lRi1Qh1mb28,27256
|
|
10
10
|
jaxsim/api/frame.py,sha256=0YXOrGmx3cSQqa4_Ky-n6zyup3I3xvXNEgub-Bc5xUw,6222
|
11
11
|
jaxsim/api/joint.py,sha256=-5DogPg4g4mmLckyVIVNjwv-Rxz0IWS7_md9nDlhPWA,4581
|
12
12
|
jaxsim/api/kin_dyn_parameters.py,sha256=zMca7OmCsCWK_cavLTSZSeYh9Qu1-409cdsyWvWPAUQ,26090
|
13
|
-
jaxsim/api/link.py,sha256=
|
13
|
+
jaxsim/api/link.py,sha256=oW5-DShmmeCRk3JOJIwzo3HbWuNGmpm_wBJ4fkmrROM,16645
|
14
14
|
jaxsim/api/model.py,sha256=1HlQ5FMzeJAk-cE1pmELgVjzMYUX9-iipw3N4WssAL4,55435
|
15
15
|
jaxsim/api/ode.py,sha256=BfvV_14uu0szWecoDiV8rTu-dvSFLK7eyrO38ZqHB_w,10157
|
16
16
|
jaxsim/api/ode_data.py,sha256=D6FzMkvY_qNuoFEImyp7sxAk-0pJOd3oZeSr9bBTcLk,23089
|
@@ -43,12 +43,12 @@ jaxsim/parsers/descriptions/model.py,sha256=uO5xOJtViihVPnSSsmfQJvCh45ANyi9KYAzL
|
|
43
43
|
jaxsim/parsers/rod/__init__.py,sha256=G2vqlLajBLUc4gyzXwsEI2Wsi4TMOIF9bLDFeT6KrGU,92
|
44
44
|
jaxsim/parsers/rod/parser.py,sha256=Q13TOkmpU0SHpgSV8WRYWb290aPNNLsaz4eMlD4Mq5w,13525
|
45
45
|
jaxsim/parsers/rod/utils.py,sha256=9oO4YsQRaR2v700IkNOXRnPpn5i4N8HFfgjPkMLK2mc,5732
|
46
|
-
jaxsim/rbda/__init__.py,sha256=
|
46
|
+
jaxsim/rbda/__init__.py,sha256=MqEZwzu8SHPAlIFHmSXmCjehuOJGRX58OrBVAbBVMwg,374
|
47
47
|
jaxsim/rbda/aba.py,sha256=0OoCzHhf1v-qqr1y5PIrD7_mPwAlid0fjXxUrIa5E_s,9118
|
48
48
|
jaxsim/rbda/collidable_points.py,sha256=4ZNJbEj2nEi15jBLR-GNbdaqKgkN58FBgqd_TXupEgg,4948
|
49
49
|
jaxsim/rbda/crba.py,sha256=GodskOZjtrSlbQAqxRv1un_706O7BaJK-U2qa18vJk8,4741
|
50
50
|
jaxsim/rbda/forward_kinematics.py,sha256=OHugNU7C0UxYAW0o1rqH1ZgniSwurz6L1T1MJxfxq08,3418
|
51
|
-
jaxsim/rbda/jacobian.py,sha256=
|
51
|
+
jaxsim/rbda/jacobian.py,sha256=M79bGir-2w_iJ2GurYhOGgMfJnp7ZMOCW6AeeWKK8iM,10745
|
52
52
|
jaxsim/rbda/rnea.py,sha256=DjwkvXQVUSUclM3Uy3UPZ2tao91R5dGd4o7TsS2qObI,7650
|
53
53
|
jaxsim/rbda/soft_contacts.py,sha256=52zJOF31hFpqoaOednTvi8j_UxhRcdGNjzOPb2v2MPc,11257
|
54
54
|
jaxsim/rbda/utils.py,sha256=zpbFM2Iq8cntku0BFVu9nfEqZhInCWi9D2INT6MFEI8,5003
|
@@ -58,8 +58,8 @@ jaxsim/utils/__init__.py,sha256=Y5zyoRevl3EMVQadhZ4EtSwTEkDt2vcnFoRhPJjKTZ0,215
|
|
58
58
|
jaxsim/utils/jaxsim_dataclass.py,sha256=h26timZ_XrBL_Q_oymv-DkQd-EcUiHn8QexAaZXBY9c,11396
|
59
59
|
jaxsim/utils/tracing.py,sha256=KDMoyVPlu2NJvFkhtZwq5AkqMMgajt3munvJom-vEjQ,650
|
60
60
|
jaxsim/utils/wrappers.py,sha256=EJMcblYKUjxw9HJShVf81Ig3pHUJno6Dx6h-RnY--wM,2040
|
61
|
-
jaxsim-0.2.1.
|
62
|
-
jaxsim-0.2.1.
|
63
|
-
jaxsim-0.2.1.
|
64
|
-
jaxsim-0.2.1.
|
65
|
-
jaxsim-0.2.1.
|
61
|
+
jaxsim-0.2.1.dev121.dist-info/LICENSE,sha256=eaYdFmdeMbiIoIiPzEK0MjP1S9wtFXjXNR5er49uLR0,1546
|
62
|
+
jaxsim-0.2.1.dev121.dist-info/METADATA,sha256=7mHvvN05TWaHWH_biQvpsOac2l8_1PyiYPXHq7Y3TEA,9745
|
63
|
+
jaxsim-0.2.1.dev121.dist-info/WHEEL,sha256=GJ7t_kWBFywbagK5eo9IoUwLW6oyOeTKmQ-9iHFVNxQ,92
|
64
|
+
jaxsim-0.2.1.dev121.dist-info/top_level.txt,sha256=LxGMA8FLtXjQ6oI7N5gd_R_oSUHxpXxUEOfT1xS_ni0,7
|
65
|
+
jaxsim-0.2.1.dev121.dist-info/RECORD,,
|
File without changes
|
File without changes
|
File without changes
|