jaxsim 0.4.2.dev31__py3-none-any.whl → 0.4.2.dev40__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.4.2.dev31'
16
- __version_tuple__ = version_tuple = (0, 4, 2, 'dev31')
15
+ __version__ = version = '0.4.2.dev40'
16
+ __version_tuple__ = version_tuple = (0, 4, 2, 'dev40')
jaxsim/api/com.py CHANGED
@@ -137,9 +137,9 @@ def centroidal_momentum_jacobian(
137
137
 
138
138
  match data.velocity_representation:
139
139
  case VelRepr.Inertial | VelRepr.Mixed:
140
- W_H_G = W_H_GW = jnp.eye(4).at[0:3, 3].set(W_p_CoM)
140
+ W_H_G = W_H_GW = jnp.eye(4).at[0:3, 3].set(W_p_CoM) # noqa: F841
141
141
  case VelRepr.Body:
142
- W_H_G = W_H_GB = W_H_B.at[0:3, 3].set(W_p_CoM)
142
+ W_H_G = W_H_GB = W_H_B.at[0:3, 3].set(W_p_CoM) # noqa: F841
143
143
  case _:
144
144
  raise ValueError(data.velocity_representation)
145
145
 
@@ -172,9 +172,9 @@ def locked_centroidal_spatial_inertia(
172
172
 
173
173
  match data.velocity_representation:
174
174
  case VelRepr.Inertial | VelRepr.Mixed:
175
- W_H_G = W_H_GW = jnp.eye(4).at[0:3, 3].set(W_p_CoM)
175
+ W_H_G = W_H_GW = jnp.eye(4).at[0:3, 3].set(W_p_CoM) # noqa: F841
176
176
  case VelRepr.Body:
177
- W_H_G = W_H_GB = W_H_B.at[0:3, 3].set(W_p_CoM)
177
+ W_H_G = W_H_GB = W_H_B.at[0:3, 3].set(W_p_CoM) # noqa: F841
178
178
  case _:
179
179
  raise ValueError(data.velocity_representation)
180
180
 
@@ -290,14 +290,14 @@ def bias_acceleration(
290
290
 
291
291
  case VelRepr.Inertial:
292
292
 
293
- C_v̇_WL = W_v̇_bias_WL = v̇_bias_WL
294
- C_v_WC = W_v_WW = jnp.zeros(6)
293
+ C_v̇_WL = W_v̇_bias_WL = v̇_bias_WL # noqa: F841
294
+ C_v_WC = W_v_WW = jnp.zeros(6) # noqa: F841
295
295
 
296
- L_H_C = L_H_W = jax.vmap(
296
+ L_H_C = L_H_W = jax.vmap( # noqa: F841
297
297
  lambda W_H_L: jaxsim.math.Transform.inverse(W_H_L)
298
298
  )(W_H_L)
299
299
 
300
- L_v_LC = L_v_LW = jax.vmap(
300
+ L_v_LC = L_v_LW = jax.vmap( # noqa: F841
301
301
  lambda i: -js.link.velocity(
302
302
  model=model, data=data, link_index=i, output_vel_repr=VelRepr.Body
303
303
  )
@@ -314,9 +314,9 @@ def bias_acceleration(
314
314
 
315
315
  case VelRepr.Mixed:
316
316
 
317
- C_v̇_WL = LW_v̇_bias_WL = v̇_bias_WL
317
+ C_v̇_WL = LW_v̇_bias_WL = v̇_bias_WL # noqa: F841
318
318
 
319
- C_v_WC = LW_v_W_LW = jax.vmap(
319
+ C_v_WC = LW_v_W_LW = jax.vmap( # noqa: F841
320
320
  lambda i: js.link.velocity(
321
321
  model=model, data=data, link_index=i, output_vel_repr=VelRepr.Mixed
322
322
  )
@@ -324,13 +324,13 @@ def bias_acceleration(
324
324
  .set(jnp.zeros(3))
325
325
  )(jnp.arange(model.number_of_links()))
326
326
 
327
- L_H_C = L_H_LW = jax.vmap(
327
+ L_H_C = L_H_LW = jax.vmap( # noqa: F841
328
328
  lambda W_H_L: jaxsim.math.Transform.inverse(
329
329
  W_H_L.at[0:3, 3].set(jnp.zeros(3))
330
330
  )
331
331
  )(W_H_L)
332
332
 
333
- L_v_LC = L_v_L_LW = jax.vmap(
333
+ L_v_LC = L_v_L_LW = jax.vmap( # noqa: F841
334
334
  lambda i: -js.link.velocity(
335
335
  model=model, data=data, link_index=i, output_vel_repr=VelRepr.Body
336
336
  )
jaxsim/api/contact.py CHANGED
@@ -537,8 +537,10 @@ def jacobian_derivative(
537
537
 
538
538
  match output_vel_repr:
539
539
  case VelRepr.Inertial:
540
- O_X_W = W_X_W = Adjoint.from_transform(transform=jnp.eye(4))
541
- O_Ẋ_W = W_Ẋ_W = jnp.zeros((6, 6))
540
+ O_X_W = W_X_W = Adjoint.from_transform( # noqa: F841
541
+ transform=jnp.eye(4)
542
+ )
543
+ O_Ẋ_W = W_Ẋ_W = jnp.zeros((6, 6)) # noqa: F841
542
544
 
543
545
  case VelRepr.Body:
544
546
  L_H_C = Transform.from_rotation_and_translation(translation=L_p_C)
@@ -548,7 +550,7 @@ def jacobian_derivative(
548
550
  W_nu = data.generalized_velocity()
549
551
  W_v_WC = W_J_WL_W[parent_link_idx] @ W_nu
550
552
  W_vx_WC = Cross.vx(W_v_WC)
551
- O_Ẋ_W = C_Ẋ_W = -C_X_W @ W_vx_WC
553
+ O_Ẋ_W = C_Ẋ_W = -C_X_W @ W_vx_WC # noqa: F841
552
554
 
553
555
  case VelRepr.Mixed:
554
556
  L_H_C = Transform.from_rotation_and_translation(translation=L_p_C)
@@ -560,7 +562,7 @@ def jacobian_derivative(
560
562
  CW_v_WC = CW_J_WC_BW @ data.generalized_velocity()
561
563
  W_v_W_CW = jnp.zeros(6).at[0:3].set(CW_v_WC[0:3])
562
564
  W_vx_W_CW = Cross.vx(W_v_W_CW)
563
- O_Ẋ_W = CW_Ẋ_W = -CW_X_W @ W_vx_W_CW
565
+ O_Ẋ_W = CW_Ẋ_W = -CW_X_W @ W_vx_W_CW # noqa: F841
564
566
 
565
567
  case _:
566
568
  raise ValueError(output_vel_repr)
jaxsim/api/frame.py CHANGED
@@ -384,7 +384,7 @@ def jacobian_derivative(
384
384
  W_nu = data.generalized_velocity()
385
385
  W_v_WF = W_J_WL_W @ W_nu
386
386
  W_vx_WF = Cross.vx(W_v_WF)
387
- O_Ẋ_W = F_Ẋ_W = -F_X_W @ W_vx_WF
387
+ O_Ẋ_W = F_Ẋ_W = -F_X_W @ W_vx_WF # noqa: F841
388
388
 
389
389
  case VelRepr.Mixed:
390
390
  W_H_F = transform(model=model, data=data, frame_index=frame_index)
@@ -401,7 +401,7 @@ def jacobian_derivative(
401
401
  FW_v_WF = FW_J_WF_FW @ data.generalized_velocity()
402
402
  W_v_W_FW = jnp.zeros(6).at[0:3].set(FW_v_WF[0:3])
403
403
  W_vx_W_FW = Cross.vx(W_v_W_FW)
404
- O_Ẋ_W = FW_Ẋ_W = -FW_X_W @ W_vx_W_FW
404
+ O_Ẋ_W = FW_Ẋ_W = -FW_X_W @ W_vx_W_FW # noqa: F841
405
405
 
406
406
  case _:
407
407
  raise ValueError(output_vel_repr)
jaxsim/api/link.py CHANGED
@@ -288,7 +288,7 @@ def jacobian(
288
288
  case VelRepr.Inertial:
289
289
  W_H_B = data.base_transform()
290
290
  B_X_W = Adjoint.from_transform(transform=W_H_B, inverse=True)
291
- B_J_WL_I = B_J_WL_W = B_J_WL_B @ jax.scipy.linalg.block_diag(
291
+ B_J_WL_I = B_J_WL_W = B_J_WL_B @ jax.scipy.linalg.block_diag( # noqa: F841
292
292
  B_X_W, jnp.eye(model.dofs())
293
293
  )
294
294
 
@@ -299,7 +299,7 @@ def jacobian(
299
299
  W_R_B = data.base_orientation(dcm=True)
300
300
  BW_H_B = jnp.eye(4).at[0:3, 0:3].set(W_R_B)
301
301
  B_X_BW = Adjoint.from_transform(transform=BW_H_B, inverse=True)
302
- B_J_WL_I = B_J_WL_BW = B_J_WL_B @ jax.scipy.linalg.block_diag(
302
+ B_J_WL_I = B_J_WL_BW = B_J_WL_B @ jax.scipy.linalg.block_diag( # noqa: F841
303
303
  B_X_BW, jnp.eye(model.dofs())
304
304
  )
305
305
 
@@ -313,7 +313,7 @@ def jacobian(
313
313
  case VelRepr.Inertial:
314
314
  W_H_B = data.base_transform()
315
315
  W_X_B = Adjoint.from_transform(transform=W_H_B)
316
- O_J_WL_I = W_J_WL_I = W_X_B @ B_J_WL_I
316
+ O_J_WL_I = W_J_WL_I = W_X_B @ B_J_WL_I # noqa: F841
317
317
 
318
318
  case VelRepr.Body:
319
319
  L_X_B = Adjoint.from_transform(transform=B_H_L, inverse=True)
@@ -505,7 +505,7 @@ def jacobian_derivative(
505
505
  with data.switch_velocity_representation(VelRepr.Body):
506
506
  B_v_WB = data.base_velocity()
507
507
 
508
- O_Ẋ_B = W_Ẋ_B = W_X_B @ jaxsim.math.Cross.vx(B_v_WB)
508
+ O_Ẋ_B = W_Ẋ_B = W_X_B @ jaxsim.math.Cross.vx(B_v_WB) # noqa: F841
509
509
 
510
510
  case VelRepr.Body:
511
511
 
@@ -519,7 +519,9 @@ def jacobian_derivative(
519
519
  B_v_WB = data.base_velocity()
520
520
  L_v_WL = js.link.velocity(model=model, data=data, link_index=link_index)
521
521
 
522
- O_Ẋ_B = L_Ẋ_B = -L_X_B @ jaxsim.math.Cross.vx(B_X_L @ L_v_WL - B_v_WB)
522
+ O_Ẋ_B = L_Ẋ_B = -L_X_B @ jaxsim.math.Cross.vx( # noqa: F841
523
+ B_X_L @ L_v_WL - B_v_WB
524
+ )
523
525
 
524
526
  case VelRepr.Mixed:
525
527
 
@@ -544,8 +546,9 @@ def jacobian_derivative(
544
546
  LW_v_LW_L = LW_v_WL - LW_v_W_LW
545
547
  LW_v_B_LW = LW_v_WL - LW_X_B @ B_v_WB - LW_v_LW_L
546
548
 
547
- O_Ẋ_B = LW_Ẋ_B = -LW_X_B @ jaxsim.math.Cross.vx(B_X_LW @ LW_v_B_LW)
548
-
549
+ O_Ẋ_B = LW_Ẋ_B = -LW_X_B @ jaxsim.math.Cross.vx( # noqa: F841
550
+ B_X_LW @ LW_v_B_LW
551
+ )
549
552
  case _:
550
553
  raise ValueError(output_vel_repr)
551
554
 
jaxsim/api/model.py CHANGED
@@ -495,8 +495,9 @@ def generalized_free_floating_jacobian(
495
495
  W_H_B = data.base_transform()
496
496
  B_X_W = Adjoint.from_transform(transform=W_H_B, inverse=True)
497
497
 
498
- B_J_full_WX_I = B_J_full_WX_W = B_J_full_WX_B @ jax.scipy.linalg.block_diag(
499
- B_X_W, jnp.eye(model.dofs())
498
+ B_J_full_WX_I = B_J_full_WX_W = ( # noqa: F841
499
+ B_J_full_WX_B
500
+ @ jax.scipy.linalg.block_diag(B_X_W, jnp.eye(model.dofs()))
500
501
  )
501
502
 
502
503
  case VelRepr.Body:
@@ -509,7 +510,7 @@ def generalized_free_floating_jacobian(
509
510
  BW_H_B = jnp.eye(4).at[0:3, 0:3].set(W_R_B)
510
511
  B_X_BW = Adjoint.from_transform(transform=BW_H_B, inverse=True)
511
512
 
512
- B_J_full_WX_I = B_J_full_WX_BW = (
513
+ B_J_full_WX_I = B_J_full_WX_BW = ( # noqa: F841
513
514
  B_J_full_WX_B
514
515
  @ jax.scipy.linalg.block_diag(B_X_BW, jnp.eye(model.dofs()))
515
516
  )
@@ -542,11 +543,13 @@ def generalized_free_floating_jacobian(
542
543
  W_H_B = data.base_transform()
543
544
  W_X_B = jaxsim.math.Adjoint.from_transform(W_H_B)
544
545
 
545
- O_J_WL_I = W_J_WL_I = jax.vmap(lambda B_J_WL_I: W_X_B @ B_J_WL_I)(B_J_WL_I)
546
+ O_J_WL_I = W_J_WL_I = jax.vmap( # noqa: F841
547
+ lambda B_J_WL_I: W_X_B @ B_J_WL_I
548
+ )(B_J_WL_I)
546
549
 
547
550
  case VelRepr.Body:
548
551
 
549
- O_J_WL_I = L_J_WL_I = jax.vmap(
552
+ O_J_WL_I = L_J_WL_I = jax.vmap( # noqa: F841
550
553
  lambda B_H_L, B_J_WL_I: jaxsim.math.Adjoint.from_transform(
551
554
  B_H_L, inverse=True
552
555
  )
@@ -565,7 +568,7 @@ def generalized_free_floating_jacobian(
565
568
  lambda LW_H_L, B_H_L: LW_H_L @ jaxsim.math.Transform.inverse(B_H_L)
566
569
  )(LW_H_L, B_H_L)
567
570
 
568
- O_J_WL_I = LW_J_WL_I = jax.vmap(
571
+ O_J_WL_I = LW_J_WL_I = jax.vmap( # noqa: F841
569
572
  lambda LW_H_B, B_J_WL_I: jaxsim.math.Adjoint.from_transform(LW_H_B)
570
573
  @ B_J_WL_I
571
574
  )(LW_H_B, B_J_WL_I)
@@ -756,8 +759,8 @@ def forward_dynamics_aba(
756
759
  match data.velocity_representation:
757
760
  case VelRepr.Inertial:
758
761
  # In this case C=W
759
- W_H_C = W_H_W = jnp.eye(4)
760
- W_v_WC = W_v_WW = jnp.zeros(6)
762
+ W_H_C = W_H_W = jnp.eye(4) # noqa: F841
763
+ W_v_WC = W_v_WW = jnp.zeros(6) # noqa: F841
761
764
 
762
765
  case VelRepr.Body:
763
766
  # In this case C=B
@@ -767,9 +770,9 @@ def forward_dynamics_aba(
767
770
  case VelRepr.Mixed:
768
771
  # In this case C=B[W]
769
772
  W_H_B = data.base_transform()
770
- W_H_C = W_H_BW = W_H_B.at[0:3, 0:3].set(jnp.eye(3))
773
+ W_H_C = W_H_BW = W_H_B.at[0:3, 0:3].set(jnp.eye(3)) # noqa: F841
771
774
  W_ṗ_B = data.base_velocity()[0:3]
772
- W_v_WC = W_v_W_BW = jnp.zeros(6).at[0:3].set(W_ṗ_B)
775
+ W_v_WC = W_v_W_BW = jnp.zeros(6).at[0:3].set(W_ṗ_B) # noqa: F841
773
776
 
774
777
  case _:
775
778
  raise ValueError(data.velocity_representation)
@@ -1124,8 +1127,8 @@ def inverse_dynamics(
1124
1127
 
1125
1128
  match data.velocity_representation:
1126
1129
  case VelRepr.Inertial:
1127
- W_H_C = W_H_W = jnp.eye(4)
1128
- W_v_WC = W_v_WW = jnp.zeros(6)
1130
+ W_H_C = W_H_W = jnp.eye(4) # noqa: F841
1131
+ W_v_WC = W_v_WW = jnp.zeros(6) # noqa: F841
1129
1132
 
1130
1133
  case VelRepr.Body:
1131
1134
  W_H_C = W_H_B = data.base_transform()
@@ -1134,9 +1137,9 @@ def inverse_dynamics(
1134
1137
 
1135
1138
  case VelRepr.Mixed:
1136
1139
  W_H_B = data.base_transform()
1137
- W_H_C = W_H_BW = W_H_B.at[0:3, 0:3].set(jnp.eye(3))
1140
+ W_H_C = W_H_BW = W_H_B.at[0:3, 0:3].set(jnp.eye(3)) # noqa: F841
1138
1141
  W_ṗ_B = data.base_velocity()[0:3]
1139
- W_v_WC = W_v_W_BW = jnp.zeros(6).at[0:3].set(W_ṗ_B)
1142
+ W_v_WC = W_v_W_BW = jnp.zeros(6).at[0:3].set(W_ṗ_B) # noqa: F841
1140
1143
 
1141
1144
  case _:
1142
1145
  raise ValueError(data.velocity_representation)
@@ -1571,15 +1574,15 @@ def link_bias_accelerations(
1571
1574
  # a simple C_X_W 6D transform.
1572
1575
  match data.velocity_representation:
1573
1576
  case VelRepr.Inertial:
1574
- W_H_C = W_H_W = jnp.eye(4)
1575
- W_v_WC = W_v_WW = jnp.zeros(6)
1577
+ W_H_C = W_H_W = jnp.eye(4) # noqa: F841
1578
+ W_v_WC = W_v_WW = jnp.zeros(6) # noqa: F841
1576
1579
  with data.switch_velocity_representation(VelRepr.Inertial):
1577
1580
  C_v_WB = W_v_WB = data.base_velocity()
1578
1581
 
1579
1582
  case VelRepr.Body:
1580
1583
  W_H_C = W_H_B
1581
1584
  with data.switch_velocity_representation(VelRepr.Inertial):
1582
- W_v_WC = W_v_WB = data.base_velocity()
1585
+ W_v_WC = W_v_WB = data.base_velocity() # noqa: F841
1583
1586
  with data.switch_velocity_representation(VelRepr.Body):
1584
1587
  C_v_WB = B_v_WB = data.base_velocity()
1585
1588
 
@@ -1590,9 +1593,9 @@ def link_bias_accelerations(
1590
1593
  W_ṗ_B = data.base_velocity()[0:3]
1591
1594
  BW_v_W_BW = jnp.zeros(6).at[0:3].set(W_ṗ_B)
1592
1595
  W_X_BW = jaxsim.math.Adjoint.from_transform(transform=W_H_BW)
1593
- W_v_WC = W_v_W_BW = W_X_BW @ BW_v_W_BW
1596
+ W_v_WC = W_v_W_BW = W_X_BW @ BW_v_W_BW # noqa: F841
1594
1597
  with data.switch_velocity_representation(VelRepr.Mixed):
1595
- C_v_WB = BW_v_WB = data.base_velocity()
1598
+ C_v_WB = BW_v_WB = data.base_velocity() # noqa: F841
1596
1599
 
1597
1600
  case _:
1598
1601
  raise ValueError(data.velocity_representation)
@@ -1700,8 +1703,12 @@ def link_bias_accelerations(
1700
1703
 
1701
1704
  match data.velocity_representation:
1702
1705
  case VelRepr.Body:
1703
- C_H_L = L_H_L = jnp.stack([jnp.eye(4)] * model.number_of_links())
1704
- L_v_CL = L_v_LL = jnp.zeros(shape=(model.number_of_links(), 6))
1706
+ C_H_L = L_H_L = jnp.stack( # noqa: F841
1707
+ [jnp.eye(4)] * model.number_of_links()
1708
+ )
1709
+ L_v_CL = L_v_LL = jnp.zeros( # noqa: F841
1710
+ shape=(model.number_of_links(), 6)
1711
+ )
1705
1712
 
1706
1713
  case VelRepr.Inertial:
1707
1714
  C_H_L = W_H_L = js.model.forward_kinematics(model=model, data=data)
@@ -1711,7 +1718,9 @@ def link_bias_accelerations(
1711
1718
  W_H_L = js.model.forward_kinematics(model=model, data=data)
1712
1719
  LW_H_L = jax.vmap(lambda W_H_L: W_H_L.at[0:3, 3].set(jnp.zeros(3)))(W_H_L)
1713
1720
  C_H_L = LW_H_L
1714
- L_v_CL = L_v_LW_L = jax.vmap(lambda v: v.at[0:3].set(jnp.zeros(3)))(L_v_WL)
1721
+ L_v_CL = L_v_LW_L = jax.vmap( # noqa: F841
1722
+ lambda v: v.at[0:3].set(jnp.zeros(3))
1723
+ )(L_v_WL)
1715
1724
 
1716
1725
  case _:
1717
1726
  raise ValueError(data.velocity_representation)
jaxsim/api/references.py CHANGED
@@ -8,6 +8,8 @@ import jax_dataclasses
8
8
 
9
9
  import jaxsim.api as js
10
10
  import jaxsim.typing as jtp
11
+ from jaxsim import exceptions
12
+ from jaxsim.math import Adjoint
11
13
  from jaxsim.utils.tracing import not_tracing
12
14
 
13
15
  from .common import VelRepr
@@ -445,3 +447,110 @@ class JaxSimModelReferences(js.common.ModelDataWithVelocityRepresentation):
445
447
  return replace(
446
448
  forces=self.input.physics_model.f_ext.at[link_idxs, :].set(W_f0_L + W_f_L)
447
449
  )
450
+
451
+ def apply_frame_forces(
452
+ self,
453
+ forces: jtp.MatrixLike,
454
+ model: js.model.JaxSimModel,
455
+ data: js.data.JaxSimModelData,
456
+ frame_names: tuple[str, ...] | str | None = None,
457
+ additive: bool = False,
458
+ ) -> Self:
459
+ """
460
+ Apply the frame forces.
461
+
462
+ Args:
463
+ forces: The frame 6D forces in the active representation.
464
+ model:
465
+ The model to consider, only needed if a frame serialization different
466
+ from the implicit one is used.
467
+ data:
468
+ The data of the considered model, only needed if the velocity
469
+ representation is not inertial-fixed.
470
+ frame_names: The names of the frames corresponding to the forces.
471
+ additive:
472
+ Whether to add the forces to the existing ones instead of replacing them.
473
+
474
+ Returns:
475
+ A new `JaxSimModelReferences` object with the given frame forces.
476
+
477
+ Note:
478
+ The frame forces must be expressed in the active representation.
479
+ Then, we always convert and store forces in inertial-fixed representation.
480
+ """
481
+
482
+ f_F = jnp.atleast_2d(forces).astype(float)
483
+
484
+ # If we have the model, we can extract the frame names if not provided.
485
+ frame_names = frame_names if frame_names is not None else model.frame_names()
486
+
487
+ # Make sure that the frame names are a tuple if they are provided by the user.
488
+ frame_names = (frame_names,) if isinstance(frame_names, str) else frame_names
489
+
490
+ if len(frame_names) != f_F.shape[0]:
491
+ msg = "The number of frame names ({}) must match the number of forces ({})"
492
+ raise ValueError(msg.format(len(frame_names), f_F.shape[0]))
493
+
494
+ # Extract the frame indices.
495
+ frame_idxs = js.frame.names_to_idxs(frame_names=frame_names, model=model)
496
+ parent_link_idxs = js.frame.idx_of_parent_link(
497
+ model=model, frame_idxs=frame_idxs
498
+ )
499
+
500
+ exceptions.raise_value_error_if(
501
+ condition=jnp.logical_not(data.valid(model=model)),
502
+ msg="The provided data is not valid for the model",
503
+ )
504
+ W_H_Fi = jax.vmap(
505
+ lambda frame_idx: js.frame.transform(
506
+ model=model, data=data, frame_index=frame_idx
507
+ )
508
+ )(frame_idxs)
509
+
510
+ # Helper function to convert a single 6D force to the inertial representation
511
+ # considering as body the frame (i.e. L_f_F and LW_f_F).
512
+ def to_inertial(f_F: jtp.MatrixLike, W_H_F: jtp.MatrixLike) -> jtp.Matrix:
513
+ return JaxSimModelReferences.other_representation_to_inertial(
514
+ array=f_F,
515
+ other_representation=self.velocity_representation,
516
+ transform=W_H_F,
517
+ is_force=True,
518
+ )
519
+
520
+ match self.velocity_representation:
521
+ case VelRepr.Inertial:
522
+ W_f_F = f_F
523
+
524
+ case VelRepr.Body | VelRepr.Mixed:
525
+ W_f_F = jax.vmap(to_inertial)(f_F, W_H_Fi, frame_idxs)
526
+
527
+ case _:
528
+ raise ValueError("Invalid velocity representation.")
529
+
530
+ W_H_L = js.model.forward_kinematics(model=model, data=data)
531
+
532
+ def convert_to_link_force(
533
+ W_f_F: jtp.MatrixLike, W_H_F: jtp.MatrixLike, parent_link_idx: jtp.ArrayLike
534
+ ) -> jtp.Matrix:
535
+ L_Xf_W = Adjoint.from_transform(W_H_L[parent_link_idx]).T
536
+
537
+ return L_Xf_W @ W_f_F
538
+
539
+ W_f_L_i = jax.vmap(convert_to_link_force)(W_f_F, W_H_Fi, parent_link_idxs)
540
+
541
+ # Sum the forces on the parent links.
542
+ mask = parent_link_idxs[:, jnp.newaxis] == jnp.arange(model.number_of_links())
543
+ W_f_L = mask.T @ W_f_L_i
544
+
545
+ with self.switch_velocity_representation(
546
+ velocity_representation=VelRepr.Inertial
547
+ ):
548
+ return self.apply_link_forces(
549
+ model=model,
550
+ data=data,
551
+ link_names=js.link.idxs_to_names(
552
+ model=model, link_indices=parent_link_idxs
553
+ ),
554
+ forces=W_f_L,
555
+ additive=additive,
556
+ )
@@ -261,8 +261,10 @@ class ExplicitRungeKutta(Integrator[PyTreeType, PyTreeType], Generic[PyTreeType]
261
261
  # Check if the Butcher tableau supports FSAL (first-same-as-last).
262
262
  # If it does, store the index of the intermediate derivative to be used as the
263
263
  # first derivative of the next iteration.
264
- has_fsal, index_of_fsal = ExplicitRungeKutta.butcher_tableau_supports_fsal(
265
- A=cls.A, b=cls.b, c=cls.c, index_of_solution=cls.row_index_of_solution
264
+ has_fsal, index_of_fsal = ( # noqa: F841
265
+ ExplicitRungeKutta.butcher_tableau_supports_fsal(
266
+ A=cls.A, b=cls.b, c=cls.c, index_of_solution=cls.row_index_of_solution
267
+ )
266
268
  )
267
269
 
268
270
  # Build the integrator object.
jaxsim/math/adjoint.py CHANGED
@@ -83,14 +83,14 @@ class Adjoint:
83
83
  A_o_B = translation.squeeze()
84
84
 
85
85
  if not inverse:
86
- X = A_X_B = jnp.vstack(
86
+ X = A_X_B = jnp.vstack( # noqa: F841
87
87
  [
88
88
  jnp.block([A_R_B, Skew.wedge(A_o_B) @ A_R_B]),
89
89
  jnp.block([jnp.zeros(shape=(3, 3)), A_R_B]),
90
90
  ]
91
91
  )
92
92
  else:
93
- X = B_X_A = jnp.vstack(
93
+ X = B_X_A = jnp.vstack( # noqa: F841
94
94
  [
95
95
  jnp.block([A_R_B.T, -A_R_B.T @ Skew.wedge(A_o_B)]),
96
96
  jnp.block([jnp.zeros(shape=(3, 3)), A_R_B.T]),
@@ -192,7 +192,7 @@ class SoftContacts(ContactModel):
192
192
 
193
193
  # Unpack the position of the collidable point.
194
194
  px, py, pz = W_p_C = position.squeeze()
195
- vx, vy, vz = W_ṗ_C = velocity.squeeze()
195
+ W_ṗ_C = velocity.squeeze()
196
196
 
197
197
  # Compute the terrain normal and the contact depth.
198
198
  n̂ = self.terrain.normal(x=px, y=py).squeeze()
@@ -1,6 +1,6 @@
1
1
  Metadata-Version: 2.1
2
2
  Name: jaxsim
3
- Version: 0.4.2.dev31
3
+ Version: 0.4.2.dev40
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>
6
6
  Maintainer-email: Diego Ferigo <dgferigo@gmail.com>, Filippo Luca Ferretti <filippo.ferretti@iit.it>
@@ -1,27 +1,27 @@
1
1
  jaxsim/__init__.py,sha256=ixsS4dYMPex2wOUUp_rkPnwrPhYzkRh1xO_YuMj3Cr4,2626
2
- jaxsim/_version.py,sha256=NaaIf0Li8SvZ9MAX4mA2JwJaZ7w3LbcXaLdVp3HJJPg,426
2
+ jaxsim/_version.py,sha256=IHeZGiBfLA-67TJBjsSwGhMy3mGUT1zOZPLh4VZCDZc,426
3
3
  jaxsim/exceptions.py,sha256=8_h8iqL8DgNR754dR8SZiQ7361GR5V1sUk3ZuZCHw1Q,2069
4
4
  jaxsim/logging.py,sha256=c4zhwBKf9eAYAHVp62kTEllqdsZgh0K-kPKVy8L3elU,1584
5
5
  jaxsim/typing.py,sha256=IbFx3UkEXi-cm7UBqMPi58rJAFV_HbZ9E_K4JwfNvVM,753
6
6
  jaxsim/api/__init__.py,sha256=8eV22t2S3UwNyCg8karPetG1dmX1VDBXkyv28_FwNQA,210
7
- jaxsim/api/com.py,sha256=6TnYCvjmsJ2KLuw3NtZb0pay7ZwGKe9MKphYeQdjpQ0,13474
7
+ jaxsim/api/com.py,sha256=m-p3EJDhpnMTlXKplfbZE_aH9NqX_VyLlAE3vUhc6l4,13642
8
8
  jaxsim/api/common.py,sha256=Ubi6uAw3o6qbdU0TFGzUyHg98EnoMzrnlihrvrs95Sk,6653
9
- jaxsim/api/contact.py,sha256=RdxPdwYbCpD_Wz0oiG9N569EoXtLiDGUAvCuoOJFYxc,19761
9
+ jaxsim/api/contact.py,sha256=yBLfjT01BxEZ1lnC0WBSJZwCXK9DnW_DBJxmo9arStE,19855
10
10
  jaxsim/api/data.py,sha256=T6m7-NteWrm-K3491Yo76xvlWtFCKqTzEE7Ughcasi8,27197
11
- jaxsim/api/frame.py,sha256=yQmhh8fckXnqzs7dQvojOzbuSanNGLwUTWUQDXbVtF4,12874
11
+ jaxsim/api/frame.py,sha256=Lsx9OIao_UZOQ6ibB_rramCRiYQbQv-M8C1QdoQdgcA,12902
12
12
  jaxsim/api/joint.py,sha256=Pvg_It2iYA-jAQ2nOlFZxwmITiozO_f46G13BdQtHQ0,5106
13
13
  jaxsim/api/kin_dyn_parameters.py,sha256=CcfSg5Mc8qb1mZeMQ4AK_ffZIsK5yOl7tu397pFhcDA,29369
14
- jaxsim/api/link.py,sha256=hn7fbxaebHeXnvwEG9jZiWwzRcfdS8m-18LVsIG3S24,18479
15
- jaxsim/api/model.py,sha256=8TTFVc7HuPLxIRq4h1pzXwuSlQ4sDVmL5KpiO-OnmnM,62662
14
+ jaxsim/api/link.py,sha256=GlnY7LMne-siFyg9J49IZGhiPQzS9Uk6rzQ0jI8cD_E,18622
15
+ jaxsim/api/model.py,sha256=EdSjpKXd4N72wYjg5o0wGKFxjVMyrXg6LnlPEi3JqnU,63094
16
16
  jaxsim/api/ode.py,sha256=NnLTBvpaT4kXnbjAghXIzLv9DTMJ8bele2iOlUQDv3Q,11028
17
17
  jaxsim/api/ode_data.py,sha256=9YZX-SK_KJtoIqG-zYWZsQInb2NA_LtxDn-jtLqm_3U,19759
18
- jaxsim/api/references.py,sha256=e8M7o4DDgfxsuJzV0WMwGbgCD-kXTDKLfJre7iwciHQ,16821
18
+ jaxsim/api/references.py,sha256=j2HFVmYUPSrHous2R8B2J8_7DPPkzS4F_6FpOoz7MQI,21034
19
19
  jaxsim/integrators/__init__.py,sha256=hxvOD-VK_mmd6v31wtC-nb28AYve1gLuZCNLV9wS-Kg,103
20
- jaxsim/integrators/common.py,sha256=iwFykYZxdchqJcmcx8MFWEVijS5Hx9wCNKLKAJdF4gE,20103
20
+ jaxsim/integrators/common.py,sha256=GqiyKTrAozuR6RuvVWdPF7locZQAXSEDY2AjTKpFGYM,20149
21
21
  jaxsim/integrators/fixed_step.py,sha256=KpjRd6hHtapxDoo6D1kyDrVDSHnke2TepI5grFH7_bM,2693
22
22
  jaxsim/integrators/variable_step.py,sha256=0FCmAZIFnhvQxVbAzNfZgCWN1yMRTGVdBm9UwwaXI1o,21280
23
23
  jaxsim/math/__init__.py,sha256=8oPITEoGwgRcOeG8KxtqxPQ8b5uku1HNRMokpCoi9Tc,352
24
- jaxsim/math/adjoint.py,sha256=MI1A6BgYGpS1dT3bQQBH66jtC08h7x5ieyAW5R6hisg,4349
24
+ jaxsim/math/adjoint.py,sha256=o1FCipkGwPtMbN2gFNIyUV8ADF3TX5fxElpTEXK0bIs,4377
25
25
  jaxsim/math/cross.py,sha256=U7yEx_l75mSy5g6O-jsjBztApvxC3WaV4MpkS5tThu4,1330
26
26
  jaxsim/math/inertia.py,sha256=UAB7ym4gXFanejcs_ovZMpteHCc6poWYmt-mLmd5hhk,1640
27
27
  jaxsim/math/joint_model.py,sha256=VZ3hRCgb0gsyI1wN1UdHkmaRMBxjAYQK1i_3WIvkdUA,9994
@@ -54,15 +54,15 @@ jaxsim/rbda/rnea.py,sha256=LGXD6s3NigaVy4-WxoROjnbKLZcUoyFmS9UNu_4ldjo,7568
54
54
  jaxsim/rbda/utils.py,sha256=eeT21Y4DiiyhrdF0lUE_VvRuwru5-rR7yOlOlWzCCWE,5381
55
55
  jaxsim/rbda/contacts/__init__.py,sha256=47DEQpj8HBSa-_TImW-5JCeuQeRkm5NMpJWZG3hSuFU,0
56
56
  jaxsim/rbda/contacts/common.py,sha256=iMKLP30Qft9eGTiHo2iY-UoACJjg1JphA9_pW8wRdjc,2410
57
- jaxsim/rbda/contacts/soft.py,sha256=3cDynim_tIgcbzRuqpHN82v4ELlxxK6lR-PG0haSK7Q,15660
57
+ jaxsim/rbda/contacts/soft.py,sha256=_wvb5iZDjGcVg6rNQelN4LZN7qSC2NIp0HdKvZmlGfk,15647
58
58
  jaxsim/terrain/__init__.py,sha256=f7lVX-iNpH_wkkjef9Qpjh19TTAUOQw76EiLYJDVizc,78
59
59
  jaxsim/terrain/terrain.py,sha256=ctyNANIFSM3tZmamprjaEDcWgUSP0oNJbmT1zw9RjPs,4565
60
60
  jaxsim/utils/__init__.py,sha256=Y5zyoRevl3EMVQadhZ4EtSwTEkDt2vcnFoRhPJjKTZ0,215
61
61
  jaxsim/utils/jaxsim_dataclass.py,sha256=fLl1tY3DDb3lpIhG6BPqA5W34hM84oFzL-5cuz8k-68,11379
62
62
  jaxsim/utils/tracing.py,sha256=KDMoyVPlu2NJvFkhtZwq5AkqMMgajt3munvJom-vEjQ,650
63
63
  jaxsim/utils/wrappers.py,sha256=GOJQCJc5zwzoEGZB62wnWWGvUUQlXvDxz_A2Q-hFv7c,4027
64
- jaxsim-0.4.2.dev31.dist-info/LICENSE,sha256=eaYdFmdeMbiIoIiPzEK0MjP1S9wtFXjXNR5er49uLR0,1546
65
- jaxsim-0.4.2.dev31.dist-info/METADATA,sha256=dnnmI39qsk5lb3hEZWe8mRZ1UntM_5KzSP5AL6S_jro,17250
66
- jaxsim-0.4.2.dev31.dist-info/WHEEL,sha256=Wyh-_nZ0DJYolHNn1_hMa4lM7uDedD_RGVwbmTjyItk,91
67
- jaxsim-0.4.2.dev31.dist-info/top_level.txt,sha256=LxGMA8FLtXjQ6oI7N5gd_R_oSUHxpXxUEOfT1xS_ni0,7
68
- jaxsim-0.4.2.dev31.dist-info/RECORD,,
64
+ jaxsim-0.4.2.dev40.dist-info/LICENSE,sha256=eaYdFmdeMbiIoIiPzEK0MjP1S9wtFXjXNR5er49uLR0,1546
65
+ jaxsim-0.4.2.dev40.dist-info/METADATA,sha256=B5lG-2DYO7EcrLg9plOEN8SAfnTKZx2zg_jreaUfRs0,17250
66
+ jaxsim-0.4.2.dev40.dist-info/WHEEL,sha256=Wyh-_nZ0DJYolHNn1_hMa4lM7uDedD_RGVwbmTjyItk,91
67
+ jaxsim-0.4.2.dev40.dist-info/top_level.txt,sha256=LxGMA8FLtXjQ6oI7N5gd_R_oSUHxpXxUEOfT1xS_ni0,7
68
+ jaxsim-0.4.2.dev40.dist-info/RECORD,,