jaxsim 0.5.1.dev147__py3-none-any.whl → 0.5.1.dev160__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/model.py +102 -105
- jaxsim/math/adjoint.py +14 -10
- jaxsim/math/cross.py +10 -5
- jaxsim/math/skew.py +14 -3
- jaxsim/math/transform.py +7 -3
- {jaxsim-0.5.1.dev147.dist-info → jaxsim-0.5.1.dev160.dist-info}/METADATA +36 -6
- {jaxsim-0.5.1.dev147.dist-info → jaxsim-0.5.1.dev160.dist-info}/RECORD +11 -11
- {jaxsim-0.5.1.dev147.dist-info → jaxsim-0.5.1.dev160.dist-info}/LICENSE +0 -0
- {jaxsim-0.5.1.dev147.dist-info → jaxsim-0.5.1.dev160.dist-info}/WHEEL +0 -0
- {jaxsim-0.5.1.dev147.dist-info → jaxsim-0.5.1.dev160.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.5.1.
|
16
|
-
__version_tuple__ = version_tuple = (0, 5, 1, '
|
15
|
+
__version__ = version = '0.5.1.dev160'
|
16
|
+
__version_tuple__ = version_tuple = (0, 5, 1, 'dev160')
|
jaxsim/api/model.py
CHANGED
@@ -736,152 +736,149 @@ def generalized_free_floating_jacobian_derivative(
|
|
736
736
|
# Compute the base transform.
|
737
737
|
W_H_B = data.base_transform()
|
738
738
|
|
739
|
-
|
740
|
-
|
741
|
-
|
742
|
-
|
743
|
-
|
744
|
-
|
745
|
-
|
739
|
+
# We add the 5 columns of ones to the Jacobian derivative to account for the
|
740
|
+
# base velocity and acceleration (5 + number of links = 6 + number of joints).
|
741
|
+
B_J̇_WL_B = (
|
742
|
+
jnp.hstack([jnp.ones((κb.shape[0], 5)), κb])[:, jnp.newaxis] * B_J̇_full_WX_B
|
743
|
+
)
|
744
|
+
B_J_WL_B = (
|
745
|
+
jnp.hstack([jnp.ones((κb.shape[0], 5)), κb])[:, jnp.newaxis] * B_J_full_WL_B
|
746
|
+
)
|
746
747
|
|
747
|
-
|
748
|
-
|
749
|
-
|
748
|
+
# =====================================================
|
749
|
+
# Compute quantities to adjust the input representation
|
750
|
+
# =====================================================
|
750
751
|
|
751
|
-
|
752
|
-
|
752
|
+
In = jnp.eye(model.dofs())
|
753
|
+
On = jnp.zeros(shape=(model.dofs(), model.dofs()))
|
753
754
|
|
754
|
-
|
755
|
-
B_J̇_WL_B = jnp.hstack([jnp.ones(5), κb]) * B_J̇_full_WX_B
|
756
|
-
B_J_WL_B = jnp.hstack([jnp.ones(5), κb]) * B_J_full_WL_B
|
755
|
+
match data.velocity_representation:
|
757
756
|
|
758
|
-
|
757
|
+
case VelRepr.Inertial:
|
759
758
|
|
760
|
-
|
759
|
+
B_X_W = jaxsim.math.Adjoint.from_transform(transform=W_H_B, inverse=True)
|
761
760
|
|
762
|
-
|
763
|
-
|
764
|
-
)
|
761
|
+
W_v_WB = data.base_velocity()
|
762
|
+
B_Ẋ_W = -B_X_W @ jaxsim.math.Cross.vx(W_v_WB)
|
765
763
|
|
766
|
-
|
767
|
-
|
764
|
+
# Compute the operator to change the representation of ν, and its
|
765
|
+
# time derivative.
|
766
|
+
T = jax.scipy.linalg.block_diag(B_X_W, In)
|
767
|
+
Ṫ = jax.scipy.linalg.block_diag(B_Ẋ_W, On)
|
768
768
|
|
769
|
-
|
770
|
-
# time derivative.
|
771
|
-
T = jax.scipy.linalg.block_diag(B_X_W, In)
|
772
|
-
Ṫ = jax.scipy.linalg.block_diag(B_Ẋ_W, On)
|
769
|
+
case VelRepr.Body:
|
773
770
|
|
774
|
-
|
771
|
+
B_X_B = jaxsim.math.Adjoint.from_rotation_and_translation(
|
772
|
+
translation=jnp.zeros(3), rotation=jnp.eye(3)
|
773
|
+
)
|
775
774
|
|
776
|
-
|
777
|
-
translation=jnp.zeros(3), rotation=jnp.eye(3)
|
778
|
-
)
|
775
|
+
B_Ẋ_B = jnp.zeros(shape=(6, 6))
|
779
776
|
|
780
|
-
|
777
|
+
# Compute the operator to change the representation of ν, and its
|
778
|
+
# time derivative.
|
779
|
+
T = jax.scipy.linalg.block_diag(B_X_B, In)
|
780
|
+
Ṫ = jax.scipy.linalg.block_diag(B_Ẋ_B, On)
|
781
781
|
|
782
|
-
|
783
|
-
# time derivative.
|
784
|
-
T = jax.scipy.linalg.block_diag(B_X_B, In)
|
785
|
-
Ṫ = jax.scipy.linalg.block_diag(B_Ẋ_B, On)
|
782
|
+
case VelRepr.Mixed:
|
786
783
|
|
787
|
-
|
784
|
+
BW_H_B = W_H_B.at[0:3, 3].set(jnp.zeros(3))
|
785
|
+
B_X_BW = jaxsim.math.Adjoint.from_transform(transform=BW_H_B, inverse=True)
|
788
786
|
|
789
|
-
|
790
|
-
|
791
|
-
transform=BW_H_B, inverse=True
|
792
|
-
)
|
787
|
+
BW_v_WB = data.base_velocity()
|
788
|
+
BW_v_W_BW = BW_v_WB.at[3:6].set(jnp.zeros(3))
|
793
789
|
|
794
|
-
|
795
|
-
|
790
|
+
BW_v_BW_B = BW_v_WB - BW_v_W_BW
|
791
|
+
B_Ẋ_BW = -B_X_BW @ jaxsim.math.Cross.vx(BW_v_BW_B)
|
796
792
|
|
797
|
-
|
798
|
-
|
793
|
+
# Compute the operator to change the representation of ν, and its
|
794
|
+
# time derivative.
|
795
|
+
T = jax.scipy.linalg.block_diag(B_X_BW, In)
|
796
|
+
Ṫ = jax.scipy.linalg.block_diag(B_Ẋ_BW, On)
|
799
797
|
|
800
|
-
|
801
|
-
|
802
|
-
T = jax.scipy.linalg.block_diag(B_X_BW, In)
|
803
|
-
Ṫ = jax.scipy.linalg.block_diag(B_Ẋ_BW, On)
|
798
|
+
case _:
|
799
|
+
raise ValueError(data.velocity_representation)
|
804
800
|
|
805
|
-
|
806
|
-
|
801
|
+
# ======================================================
|
802
|
+
# Compute quantities to adjust the output representation
|
803
|
+
# ======================================================
|
807
804
|
|
808
|
-
|
809
|
-
# Compute quantities to adjust the output representation
|
810
|
-
# ======================================================
|
805
|
+
match output_vel_repr:
|
811
806
|
|
812
|
-
|
807
|
+
case VelRepr.Inertial:
|
813
808
|
|
814
|
-
|
809
|
+
O_X_B = W_X_B = jaxsim.math.Adjoint.from_transform(transform=W_H_B)
|
815
810
|
|
816
|
-
|
811
|
+
with data.switch_velocity_representation(VelRepr.Body):
|
812
|
+
B_v_WB = data.base_velocity()
|
817
813
|
|
818
|
-
|
819
|
-
B_v_WB = data.base_velocity()
|
814
|
+
O_Ẋ_B = W_Ẋ_B = W_X_B @ jaxsim.math.Cross.vx(B_v_WB) # noqa: F841
|
820
815
|
|
821
|
-
|
816
|
+
case VelRepr.Body:
|
822
817
|
|
823
|
-
|
818
|
+
O_X_B = L_X_B = jaxsim.math.Adjoint.from_transform(
|
819
|
+
transform=B_H_L, inverse=True
|
820
|
+
)
|
824
821
|
|
825
|
-
|
826
|
-
transform=B_H_L, inverse=True
|
827
|
-
)
|
822
|
+
B_X_L = jaxsim.math.Adjoint.inverse(adjoint=L_X_B)
|
828
823
|
|
829
|
-
|
824
|
+
with data.switch_velocity_representation(VelRepr.Body):
|
825
|
+
B_v_WB = data.base_velocity()
|
826
|
+
L_v_WL = jnp.einsum(
|
827
|
+
"b6j,j->b6", L_X_B @ B_J_WL_B, data.generalized_velocity()
|
828
|
+
)
|
830
829
|
|
831
|
-
|
832
|
-
|
833
|
-
|
830
|
+
O_Ẋ_B = L_Ẋ_B = -L_X_B @ jaxsim.math.Cross.vx( # noqa: F841
|
831
|
+
jnp.einsum("bij,bj->bi", B_X_L, L_v_WL) - B_v_WB
|
832
|
+
)
|
834
833
|
|
835
|
-
|
836
|
-
B_X_L @ L_v_WL - B_v_WB
|
837
|
-
)
|
834
|
+
case VelRepr.Mixed:
|
838
835
|
|
839
|
-
|
836
|
+
W_H_L = W_H_B @ B_H_L
|
837
|
+
LW_H_L = W_H_L.at[:, 0:3, 3].set(jnp.zeros_like(W_H_L[:, 0:3, 3]))
|
838
|
+
LW_H_B = LW_H_L @ jaxsim.math.Transform.inverse(B_H_L)
|
840
839
|
|
841
|
-
|
842
|
-
LW_H_L = W_H_L.at[0:3, 3].set(jnp.zeros(3))
|
843
|
-
LW_H_B = LW_H_L @ jaxsim.math.Transform.inverse(B_H_L)
|
840
|
+
O_X_B = LW_X_B = jaxsim.math.Adjoint.from_transform(transform=LW_H_B)
|
844
841
|
|
845
|
-
|
842
|
+
B_X_LW = jaxsim.math.Adjoint.inverse(adjoint=LW_X_B)
|
846
843
|
|
847
|
-
|
844
|
+
with data.switch_velocity_representation(VelRepr.Body):
|
845
|
+
B_v_WB = data.base_velocity()
|
848
846
|
|
849
|
-
|
850
|
-
|
847
|
+
with data.switch_velocity_representation(VelRepr.Mixed):
|
848
|
+
BW_H_B = W_H_B.at[0:3, 3].set(jnp.zeros(3))
|
849
|
+
B_X_BW = Adjoint.from_transform(transform=BW_H_B, inverse=True)
|
850
|
+
LW_v_WL = jnp.einsum(
|
851
|
+
"bij,bj->bi",
|
852
|
+
LW_X_B,
|
853
|
+
B_J_WL_B
|
854
|
+
@ jax.scipy.linalg.block_diag(B_X_BW, jnp.eye(model.dofs()))
|
855
|
+
@ data.generalized_velocity(),
|
856
|
+
)
|
851
857
|
|
852
|
-
|
853
|
-
BW_H_B = W_H_B.at[0:3, 3].set(jnp.zeros(3))
|
854
|
-
B_X_BW = Adjoint.from_transform(transform=BW_H_B, inverse=True)
|
855
|
-
LW_v_WL = LW_X_B @ (
|
856
|
-
B_J_WL_B
|
857
|
-
@ jax.scipy.linalg.block_diag(B_X_BW, jnp.eye(model.dofs()))
|
858
|
-
@ data.generalized_velocity()
|
859
|
-
)
|
860
|
-
LW_v_W_LW = LW_v_WL.at[3:6].set(jnp.zeros(3))
|
858
|
+
LW_v_W_LW = LW_v_WL.at[:, 3:6].set(jnp.zeros_like(LW_v_WL[:, 3:6]))
|
861
859
|
|
862
|
-
|
863
|
-
|
860
|
+
LW_v_LW_L = LW_v_WL - LW_v_W_LW
|
861
|
+
LW_v_B_LW = LW_v_WL - jnp.einsum("bij,j->bi", LW_X_B, B_v_WB) - LW_v_LW_L
|
864
862
|
|
865
|
-
|
866
|
-
|
867
|
-
|
868
|
-
case _:
|
869
|
-
raise ValueError(output_vel_repr)
|
863
|
+
O_Ẋ_B = LW_Ẋ_B = -LW_X_B @ jaxsim.math.Cross.vx( # noqa: F841
|
864
|
+
jnp.einsum("bij,bj->bi", B_X_LW, LW_v_B_LW)
|
865
|
+
)
|
870
866
|
|
871
|
-
|
872
|
-
|
873
|
-
# =============================================================
|
867
|
+
case _:
|
868
|
+
raise ValueError(output_vel_repr)
|
874
869
|
|
875
|
-
|
876
|
-
|
877
|
-
|
878
|
-
O_J̇_WL_I += O_Ẋ_B @ B_J_WL_B @ T
|
879
|
-
O_J̇_WL_I += O_X_B @ B_J̇_WL_B @ T
|
880
|
-
O_J̇_WL_I += O_X_B @ B_J_WL_B @ Ṫ
|
870
|
+
# =============================================================
|
871
|
+
# Express the Jacobian derivative in the target representations
|
872
|
+
# =============================================================
|
881
873
|
|
882
|
-
|
874
|
+
# Sum all the components that form the Jacobian derivative in the target
|
875
|
+
# input/output velocity representations.
|
876
|
+
O_J̇_WL_I = jnp.zeros_like(B_J̇_WL_B)
|
877
|
+
O_J̇_WL_I += O_Ẋ_B @ B_J_WL_B @ T
|
878
|
+
O_J̇_WL_I += O_X_B @ B_J̇_WL_B @ T
|
879
|
+
O_J̇_WL_I += O_X_B @ B_J_WL_B @ Ṫ
|
883
880
|
|
884
|
-
return
|
881
|
+
return O_J̇_WL_I
|
885
882
|
|
886
883
|
|
887
884
|
@functools.partial(jax.jit, static_argnames=["prefer_aba"])
|
jaxsim/math/adjoint.py
CHANGED
@@ -56,14 +56,13 @@ class Adjoint:
|
|
56
56
|
The 6x6 adjoint matrix.
|
57
57
|
"""
|
58
58
|
|
59
|
-
A_H_B = jnp.
|
60
|
-
assert transform.shape == (4, 4)
|
59
|
+
A_H_B = jnp.reshape(transform, (-1, 4, 4))
|
61
60
|
|
62
61
|
return (
|
63
62
|
jaxlie.SE3.from_matrix(matrix=A_H_B).adjoint()
|
64
63
|
if not inverse
|
65
64
|
else jaxlie.SE3.from_matrix(matrix=A_H_B).inverse().adjoint()
|
66
|
-
)
|
65
|
+
).reshape(transform.shape[:-2] + (6, 6))
|
67
66
|
|
68
67
|
@staticmethod
|
69
68
|
def from_rotation_and_translation(
|
@@ -145,13 +144,18 @@ class Adjoint:
|
|
145
144
|
Returns:
|
146
145
|
jtp.Matrix: The inverse adjoint matrix.
|
147
146
|
"""
|
148
|
-
A_X_B = adjoint
|
147
|
+
A_X_B = adjoint.reshape(-1, 6, 6)
|
149
148
|
|
150
|
-
|
149
|
+
A_R_B_T = jnp.swapaxes(A_X_B[..., 0:3, 0:3], -2, -1)
|
150
|
+
A_T_B = A_X_B[..., 0:3, 3:6]
|
151
151
|
|
152
|
-
return jnp.
|
152
|
+
return jnp.concatenate(
|
153
153
|
[
|
154
|
-
jnp.
|
155
|
-
|
156
|
-
|
157
|
-
|
154
|
+
jnp.concatenate(
|
155
|
+
[A_R_B_T, -A_R_B_T @ A_T_B @ A_R_B_T],
|
156
|
+
axis=-1,
|
157
|
+
),
|
158
|
+
jnp.concatenate([jnp.zeros_like(A_R_B_T), A_R_B_T], axis=-1),
|
159
|
+
],
|
160
|
+
axis=-2,
|
161
|
+
).reshape(adjoint.shape)
|
jaxsim/math/cross.py
CHANGED
@@ -24,13 +24,18 @@ class Cross:
|
|
24
24
|
Raises:
|
25
25
|
ValueError: If the input vector does not have a size of 6.
|
26
26
|
"""
|
27
|
-
|
27
|
+
velocity_sixd = velocity_sixd.reshape(-1, 6)
|
28
28
|
|
29
|
-
|
29
|
+
v, ω = jnp.split(velocity_sixd, 2, axis=-1)
|
30
|
+
|
31
|
+
v_cross = jnp.concatenate(
|
30
32
|
[
|
31
|
-
jnp.
|
32
|
-
|
33
|
-
|
33
|
+
jnp.concatenate(
|
34
|
+
[Skew.wedge(ω), jnp.zeros((ω.shape[0], 3, 3)).squeeze()], axis=-2
|
35
|
+
),
|
36
|
+
jnp.concatenate([Skew.wedge(v), Skew.wedge(ω)], axis=-2),
|
37
|
+
],
|
38
|
+
axis=-1,
|
34
39
|
)
|
35
40
|
|
36
41
|
return v_cross
|
jaxsim/math/skew.py
CHANGED
@@ -20,9 +20,20 @@ class Skew:
|
|
20
20
|
jtp.Matrix: The skew-symmetric matrix corresponding to the input vector.
|
21
21
|
|
22
22
|
"""
|
23
|
-
|
24
|
-
|
25
|
-
|
23
|
+
|
24
|
+
vector = vector.reshape(-1, 3)
|
25
|
+
|
26
|
+
x, y, z = jnp.split(vector, 3, axis=-1)
|
27
|
+
|
28
|
+
skew = jnp.stack(
|
29
|
+
[
|
30
|
+
jnp.concatenate([jnp.zeros_like(x), -z, y], axis=-1),
|
31
|
+
jnp.concatenate([z, jnp.zeros_like(x), -x], axis=-1),
|
32
|
+
jnp.concatenate([-y, x, jnp.zeros_like(x)], axis=-1),
|
33
|
+
],
|
34
|
+
axis=-2,
|
35
|
+
).squeeze()
|
36
|
+
|
26
37
|
return skew
|
27
38
|
|
28
39
|
@staticmethod
|
jaxsim/math/transform.py
CHANGED
@@ -92,7 +92,11 @@ class Transform:
|
|
92
92
|
The 4x4 inverse transformation matrix.
|
93
93
|
"""
|
94
94
|
|
95
|
-
A_H_B = jnp.
|
96
|
-
assert A_H_B.shape == (4, 4)
|
95
|
+
A_H_B = jnp.reshape(transform, (-1, 4, 4))
|
97
96
|
|
98
|
-
return
|
97
|
+
return (
|
98
|
+
jaxlie.SE3.from_matrix(matrix=A_H_B)
|
99
|
+
.inverse()
|
100
|
+
.as_matrix()
|
101
|
+
.reshape(transform.shape[:-2] + (4, 4))
|
102
|
+
)
|
@@ -1,6 +1,6 @@
|
|
1
1
|
Metadata-Version: 2.2
|
2
2
|
Name: jaxsim
|
3
|
-
Version: 0.5.1.
|
3
|
+
Version: 0.5.1.dev160
|
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>
|
@@ -237,16 +237,30 @@ You can enforce GPU support, if needed, by also specifying `"jaxlib = * = *cuda*
|
|
237
237
|
<details>
|
238
238
|
<summary>With <code>pixi</code></summary>
|
239
239
|
|
240
|
-
>
|
240
|
+
> ### Note
|
241
241
|
> The minimum version of `pixi` required is `0.39.0`.
|
242
242
|
|
243
|
-
You can
|
243
|
+
You can add the jaxsim dependency in [`pixi`][pixi] project as follows:
|
244
244
|
|
245
245
|
```bash
|
246
|
-
pixi
|
246
|
+
pixi add jaxsim
|
247
247
|
```
|
248
248
|
|
249
|
-
|
249
|
+
If you are on Linux and you want to use a `cuda`-powered version of `jax`, remember to add the appropriate line in the [`system-requirements`](https://pixi.sh/latest/reference/pixi_manifest/#the-system-requirements-table) table, i.e. adding
|
250
|
+
|
251
|
+
~~~toml
|
252
|
+
[system-requirements]
|
253
|
+
cuda = "12"
|
254
|
+
~~~
|
255
|
+
|
256
|
+
if you are using a `pixi.toml` file or
|
257
|
+
|
258
|
+
~~~toml
|
259
|
+
[tool.pixi.system-requirements]
|
260
|
+
cuda = "12"
|
261
|
+
~~~
|
262
|
+
|
263
|
+
if you are using a `pyproject.toml` file.
|
250
264
|
|
251
265
|
</details>
|
252
266
|
|
@@ -267,7 +281,7 @@ If you need GPU support, follow the official [installation instructions][jax_gpu
|
|
267
281
|
</details>
|
268
282
|
|
269
283
|
<details>
|
270
|
-
<summary>Contributors installation</summary>
|
284
|
+
<summary>Contributors installation (with <code>conda</code>)</summary>
|
271
285
|
|
272
286
|
If you want to contribute to the project, we recommend creating the following `jaxsim` conda environment first:
|
273
287
|
|
@@ -284,6 +298,22 @@ pip install --no-deps -e .
|
|
284
298
|
|
285
299
|
</details>
|
286
300
|
|
301
|
+
<details>
|
302
|
+
<summary>Contributors installation (with <code>pixi</code>)</summary>
|
303
|
+
|
304
|
+
> ### Note
|
305
|
+
> The minimum version of `pixi` required is `0.39.0`.
|
306
|
+
|
307
|
+
You can install the default dependencies of the project using [`pixi`][pixi] as follows:
|
308
|
+
|
309
|
+
```bash
|
310
|
+
pixi install
|
311
|
+
```
|
312
|
+
|
313
|
+
See `pixi task list` for a list of available tasks.
|
314
|
+
|
315
|
+
</details>
|
316
|
+
|
287
317
|
[conda]: https://anaconda.org/
|
288
318
|
[pip]: https://github.com/pypa/pip/
|
289
319
|
[pixi]: https://pixi.sh/
|
@@ -1,5 +1,5 @@
|
|
1
1
|
jaxsim/__init__.py,sha256=_8rbKOf3bwx-2ChEbspZxs_rZY0RqUcmWAftnEw1bfM,3401
|
2
|
-
jaxsim/_version.py,sha256=
|
2
|
+
jaxsim/_version.py,sha256=LFzsk7IuMCWjONW-0TMiOLJ2B9UR9fM3LGiij2F17N4,428
|
3
3
|
jaxsim/exceptions.py,sha256=qjfTjE9lXvD3-JCPQcxxiX2XSS8QegawzQ6ZuC2tc0Y,2638
|
4
4
|
jaxsim/logging.py,sha256=STI-D_upXZYX-ZezLrlJJ0UlD5YspST0vZ_DcIwkzO4,1553
|
5
5
|
jaxsim/typing.py,sha256=7msl8t5Jt09RNYfKdPJtpjLfWurldcycDappb045Eso,761
|
@@ -12,7 +12,7 @@ jaxsim/api/frame.py,sha256=d6pa6vywGDqfaJU76F_-yjLJs6R3mrjZ6B-KXPu6f3Q,14595
|
|
12
12
|
jaxsim/api/joint.py,sha256=AnqlNWmBOay-gsoo0y4AbfFQ2OCJm-8T1E0IMhZeLoY,7457
|
13
13
|
jaxsim/api/kin_dyn_parameters.py,sha256=BaOp7ICxWosDIdWVjh8-cdlX8mXM9IM8wzy2fHz8Ufc,30444
|
14
14
|
jaxsim/api/link.py,sha256=nHjffhNdi_xGkteMsqdb_hC9mdV9rNw7k3pl89Uhw_8,12798
|
15
|
-
jaxsim/api/model.py,sha256=
|
15
|
+
jaxsim/api/model.py,sha256=27U_3JxEvbCyPox76h2uxIKnpFHahxsGZCYZQy1vXf4,79859
|
16
16
|
jaxsim/api/ode.py,sha256=XFi3gGRU2s-hqOpZEAuk7o4cxEa871V1LmGcvT5wf10,16056
|
17
17
|
jaxsim/api/ode_data.py,sha256=ggF1AVaLW5QuXrfpNsFs-voVcW6gZkxK2Xe9GiDmou0,13755
|
18
18
|
jaxsim/api/references.py,sha256=YkdZhRv8NoBC94qvpwn1w9_alVuxrfiZV5w5NHQIt-g,20737
|
@@ -21,14 +21,14 @@ jaxsim/integrators/common.py,sha256=sXc0HLmqiGluU-ffsNcAxVO-UA4QzS96pjef5N-5rHI,
|
|
21
21
|
jaxsim/integrators/fixed_step.py,sha256=roiRR1evnQMPmdvY5D_iRHTYlbOvkG4CM6JDSqlmTAU,4034
|
22
22
|
jaxsim/integrators/variable_step.py,sha256=pMYiMbaqQTlq2VF4Ca78ovxU06lMF1mrnrfzAahtvcg,24577
|
23
23
|
jaxsim/math/__init__.py,sha256=2T1WUU_chNBCvyvkKSdiesPlckbo-gXVbCZEGoF-W0I,381
|
24
|
-
jaxsim/math/adjoint.py,sha256=
|
25
|
-
jaxsim/math/cross.py,sha256=
|
24
|
+
jaxsim/math/adjoint.py,sha256=ccXuF9jnMLpGhQ3vg1hu7V6zUz8D3rVMhj-bongdk9c,5019
|
25
|
+
jaxsim/math/cross.py,sha256=brlzoThCzQAHmuHubh1N_CLtvP5asR4iWXp-I1HAYFc,1522
|
26
26
|
jaxsim/math/inertia.py,sha256=Bh92FlJvJMMZg8825mzEzV3sHAAufJOSaQST1ZnzgSQ,1631
|
27
27
|
jaxsim/math/joint_model.py,sha256=EzAveaG5B6ZnCFNUzN30KEQUVesd83lfWXJarYR-kUw,9989
|
28
28
|
jaxsim/math/quaternion.py,sha256=fO3VNrIoZrcchCXCv_Zn2Ad6-rcgrNzysRrn5raQWJE,4595
|
29
29
|
jaxsim/math/rotation.py,sha256=bl9WCbYyLKg6RyRkMaEBBTmARBs8pB-FGR0JVbfbaNE,2187
|
30
|
-
jaxsim/math/skew.py,sha256=
|
31
|
-
jaxsim/math/transform.py,sha256=
|
30
|
+
jaxsim/math/skew.py,sha256=P82yeQs9Fzb7Ri_MAikcb54_06cE_syi9yPssSg4ydw,1426
|
31
|
+
jaxsim/math/transform.py,sha256=We0ChLajSckxGINiJsP1a5Ur3yjg3JuweQ3kK4Woix4,3332
|
32
32
|
jaxsim/math/utils.py,sha256=2id1F6QOvkHkIF3Nuxuj_tz_kI0IYlrlgVQrETmXFfI,1058
|
33
33
|
jaxsim/mujoco/__init__.py,sha256=fZyRWre49pIhOrYdf6yJk_hOax8qWGe8OCmoq-dMVq8,201
|
34
34
|
jaxsim/mujoco/__main__.py,sha256=GBmB7J-zj75ZnFyuAAmpSOpbxi_HhHhWJeot3ljGDJY,5291
|
@@ -67,8 +67,8 @@ jaxsim/utils/__init__.py,sha256=Y5zyoRevl3EMVQadhZ4EtSwTEkDt2vcnFoRhPJjKTZ0,215
|
|
67
67
|
jaxsim/utils/jaxsim_dataclass.py,sha256=Fxa555u14VUsVlKU1rBQFurrVzBp7BNsIaVoNko0lrI,11261
|
68
68
|
jaxsim/utils/tracing.py,sha256=Btwxdfhb7fJLk3r5PlQkGYj60Y2KbFT1gANGIA697FU,530
|
69
69
|
jaxsim/utils/wrappers.py,sha256=3IMwydqFgmSPqeuUQ3PRmdhDc1IoT6XC23jPC_LjWXs,4175
|
70
|
-
jaxsim-0.5.1.
|
71
|
-
jaxsim-0.5.1.
|
72
|
-
jaxsim-0.5.1.
|
73
|
-
jaxsim-0.5.1.
|
74
|
-
jaxsim-0.5.1.
|
70
|
+
jaxsim-0.5.1.dev160.dist-info/LICENSE,sha256=eaYdFmdeMbiIoIiPzEK0MjP1S9wtFXjXNR5er49uLR0,1546
|
71
|
+
jaxsim-0.5.1.dev160.dist-info/METADATA,sha256=zujfy9xVKXUkRBBa-5weqc0q8Xy-dEEgIqjyZzidR9A,20201
|
72
|
+
jaxsim-0.5.1.dev160.dist-info/WHEEL,sha256=In9FTNxeP60KnTkGw7wk6mJPYd_dQSjEZmXdBdMCI-8,91
|
73
|
+
jaxsim-0.5.1.dev160.dist-info/top_level.txt,sha256=LxGMA8FLtXjQ6oI7N5gd_R_oSUHxpXxUEOfT1xS_ni0,7
|
74
|
+
jaxsim-0.5.1.dev160.dist-info/RECORD,,
|
File without changes
|
File without changes
|
File without changes
|