jaxsim 0.4.3.dev271__py3-none-any.whl → 0.4.3.dev282__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/joint.py +5 -2
- jaxsim/api/ode.py +32 -1
- jaxsim/math/rotation.py +26 -12
- jaxsim/parsers/rod/parser.py +3 -2
- {jaxsim-0.4.3.dev271.dist-info → jaxsim-0.4.3.dev282.dist-info}/METADATA +1 -1
- {jaxsim-0.4.3.dev271.dist-info → jaxsim-0.4.3.dev282.dist-info}/RECORD +10 -10
- {jaxsim-0.4.3.dev271.dist-info → jaxsim-0.4.3.dev282.dist-info}/LICENSE +0 -0
- {jaxsim-0.4.3.dev271.dist-info → jaxsim-0.4.3.dev282.dist-info}/WHEEL +0 -0
- {jaxsim-0.4.3.dev271.dist-info → jaxsim-0.4.3.dev282.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.4.3.
|
16
|
-
__version_tuple__ = version_tuple = (0, 4, 3, '
|
15
|
+
__version__ = version = '0.4.3.dev282'
|
16
|
+
__version_tuple__ = version_tuple = (0, 4, 3, 'dev282')
|
jaxsim/api/joint.py
CHANGED
@@ -122,8 +122,11 @@ def position_limit(
|
|
122
122
|
The position limits of the joint.
|
123
123
|
"""
|
124
124
|
|
125
|
-
if model.number_of_joints()
|
126
|
-
|
125
|
+
if model.number_of_joints() == 0:
|
126
|
+
s_min = model.kin_dyn_parameters.joint_parameters.position_limits_min
|
127
|
+
s_max = model.kin_dyn_parameters.joint_parameters.position_limits_max
|
128
|
+
|
129
|
+
return jnp.atleast_1d(s_min).astype(float), jnp.atleast_1d(s_max).astype(float)
|
127
130
|
|
128
131
|
exceptions.raise_value_error_if(
|
129
132
|
condition=jnp.array(
|
jaxsim/api/ode.py
CHANGED
@@ -243,9 +243,40 @@ def system_acceleration(
|
|
243
243
|
# Enforce joint limits
|
244
244
|
# ====================
|
245
245
|
|
246
|
-
# TODO: enforce joint limits
|
247
246
|
τ_position_limit = jnp.zeros_like(τ_references).astype(float)
|
248
247
|
|
248
|
+
if model.dofs() > 0:
|
249
|
+
|
250
|
+
# Stiffness and damper parameters for the joint position limits.
|
251
|
+
k_j = jnp.array(
|
252
|
+
model.kin_dyn_parameters.joint_parameters.position_limit_spring
|
253
|
+
).astype(float)
|
254
|
+
d_j = jnp.array(
|
255
|
+
model.kin_dyn_parameters.joint_parameters.position_limit_damper
|
256
|
+
).astype(float)
|
257
|
+
|
258
|
+
# Compute the joint position limit violations.
|
259
|
+
lower_violation = jnp.clip(
|
260
|
+
data.state.physics_model.joint_positions
|
261
|
+
- model.kin_dyn_parameters.joint_parameters.position_limits_min,
|
262
|
+
max=0.0,
|
263
|
+
)
|
264
|
+
|
265
|
+
upper_violation = jnp.clip(
|
266
|
+
data.state.physics_model.joint_positions
|
267
|
+
- model.kin_dyn_parameters.joint_parameters.position_limits_max,
|
268
|
+
min=0.0,
|
269
|
+
)
|
270
|
+
|
271
|
+
# Compute the joint position limit torque.
|
272
|
+
τ_position_limit -= jnp.diag(k_j) @ (lower_violation + upper_violation)
|
273
|
+
|
274
|
+
τ_position_limit -= (
|
275
|
+
jnp.positive(τ_position_limit)
|
276
|
+
* jnp.diag(d_j)
|
277
|
+
@ data.state.physics_model.joint_velocities
|
278
|
+
)
|
279
|
+
|
249
280
|
# ====================
|
250
281
|
# Joint friction model
|
251
282
|
# ====================
|
jaxsim/math/rotation.py
CHANGED
@@ -1,4 +1,3 @@
|
|
1
|
-
import jax
|
2
1
|
import jax.numpy as jnp
|
3
2
|
import jaxlie
|
4
3
|
|
@@ -8,6 +7,7 @@ from .skew import Skew
|
|
8
7
|
|
9
8
|
|
10
9
|
class Rotation:
|
10
|
+
|
11
11
|
@staticmethod
|
12
12
|
def x(theta: jtp.Float) -> jtp.Matrix:
|
13
13
|
"""
|
@@ -19,6 +19,7 @@ class Rotation:
|
|
19
19
|
Returns:
|
20
20
|
jtp.Matrix: 3D rotation matrix.
|
21
21
|
"""
|
22
|
+
|
22
23
|
return jaxlie.SO3.from_x_radians(theta=theta).as_matrix()
|
23
24
|
|
24
25
|
@staticmethod
|
@@ -32,6 +33,7 @@ class Rotation:
|
|
32
33
|
Returns:
|
33
34
|
jtp.Matrix: 3D rotation matrix.
|
34
35
|
"""
|
36
|
+
|
35
37
|
return jaxlie.SO3.from_y_radians(theta=theta).as_matrix()
|
36
38
|
|
37
39
|
@staticmethod
|
@@ -45,6 +47,7 @@ class Rotation:
|
|
45
47
|
Returns:
|
46
48
|
jtp.Matrix: 3D rotation matrix.
|
47
49
|
"""
|
50
|
+
|
48
51
|
return jaxlie.SO3.from_z_radians(theta=theta).as_matrix()
|
49
52
|
|
50
53
|
@staticmethod
|
@@ -53,17 +56,18 @@ class Rotation:
|
|
53
56
|
Generate a 3D rotation matrix from an axis-angle representation.
|
54
57
|
|
55
58
|
Args:
|
56
|
-
vector
|
59
|
+
vector: Axis-angle representation or the rotation as a 3D vector.
|
57
60
|
|
58
61
|
Returns:
|
59
|
-
|
60
|
-
|
62
|
+
The SO(3) rotation matrix.
|
61
63
|
"""
|
64
|
+
|
62
65
|
vector = vector.squeeze()
|
63
|
-
theta = jnp.linalg.norm(vector)
|
64
66
|
|
65
|
-
def theta_is_not_zero(
|
66
|
-
|
67
|
+
def theta_is_not_zero(axis: jtp.Vector) -> jtp.Matrix:
|
68
|
+
|
69
|
+
v = axis
|
70
|
+
theta = jnp.linalg.norm(v)
|
67
71
|
|
68
72
|
s = jnp.sin(theta)
|
69
73
|
c = jnp.cos(theta)
|
@@ -77,9 +81,19 @@ class Rotation:
|
|
77
81
|
|
78
82
|
return R.transpose()
|
79
83
|
|
80
|
-
|
81
|
-
|
82
|
-
|
83
|
-
|
84
|
-
|
84
|
+
# Use the double-where trick to prevent JAX problems when the
|
85
|
+
# jax.jit and jax.grad transforms are applied.
|
86
|
+
return jnp.where(
|
87
|
+
jnp.linalg.norm(vector) > 0,
|
88
|
+
theta_is_not_zero(
|
89
|
+
axis=jnp.where(
|
90
|
+
jnp.linalg.norm(vector) > 0,
|
91
|
+
vector,
|
92
|
+
# The following line is a workaround to prevent division by 0.
|
93
|
+
# Considering the outer where, this branch is never executed.
|
94
|
+
jnp.ones(3),
|
95
|
+
)
|
96
|
+
),
|
97
|
+
# Return an identity rotation matrix when the input vector is zero.
|
98
|
+
jnp.eye(3),
|
85
99
|
)
|
jaxsim/parsers/rod/parser.py
CHANGED
@@ -1,4 +1,5 @@
|
|
1
1
|
import dataclasses
|
2
|
+
import os
|
2
3
|
import pathlib
|
3
4
|
from typing import NamedTuple
|
4
5
|
|
@@ -273,14 +274,14 @@ def extract_model_data(
|
|
273
274
|
if j.axis is not None
|
274
275
|
and j.axis.limit is not None
|
275
276
|
and j.axis.limit.dissipation is not None
|
276
|
-
else 0.0
|
277
|
+
else os.environ.get("JAXSIM_JOINT_POSITION_LIMIT_DAMPER", 0.0)
|
277
278
|
),
|
278
279
|
position_limit_spring=float(
|
279
280
|
j.axis.limit.stiffness
|
280
281
|
if j.axis is not None
|
281
282
|
and j.axis.limit is not None
|
282
283
|
and j.axis.limit.stiffness is not None
|
283
|
-
else 0.0
|
284
|
+
else os.environ.get("JAXSIM_JOINT_POSITION_LIMIT_SPRING", 0.0)
|
284
285
|
),
|
285
286
|
)
|
286
287
|
for j in sdf_model.joints()
|
@@ -1,6 +1,6 @@
|
|
1
1
|
Metadata-Version: 2.1
|
2
2
|
Name: jaxsim
|
3
|
-
Version: 0.4.3.
|
3
|
+
Version: 0.4.3.dev282
|
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,5 +1,5 @@
|
|
1
1
|
jaxsim/__init__.py,sha256=opgtbhhd1kDsHI4H1vOd3loMPDRi884yQ3tohfFGfNc,3382
|
2
|
-
jaxsim/_version.py,sha256=
|
2
|
+
jaxsim/_version.py,sha256=8Lzzuj01bYiR6tHmTBRLQW2sSRCWlBO6B-razI_HdjU,428
|
3
3
|
jaxsim/exceptions.py,sha256=vSoScaRD4nvh6jltgK9Ry5pKnE0O5hb4_yI_pk_fvR8,2175
|
4
4
|
jaxsim/logging.py,sha256=STI-D_upXZYX-ZezLrlJJ0UlD5YspST0vZ_DcIwkzO4,1553
|
5
5
|
jaxsim/typing.py,sha256=2HXy9hgazPXjofi1vLQ09ZubPtgVmg80U9NKmZ6NYiI,761
|
@@ -9,11 +9,11 @@ jaxsim/api/common.py,sha256=SNgxq42r6eF_-aPszvOjUYkGwXOzz4hKmhDwEUkscFQ,6650
|
|
9
9
|
jaxsim/api/contact.py,sha256=iiQc8vdlJ60Vl-ki4ieP7TW6MJhJfWREYpcVyyEWT0M,24034
|
10
10
|
jaxsim/api/data.py,sha256=gQX6hfEaw0ooJYvpr5f8UvEJwqhtflEK_NHWn9XgTZY,28935
|
11
11
|
jaxsim/api/frame.py,sha256=yPSgNygHkvWlln4wShNt7vZm_fFobVEm7phsklNNyH8,12922
|
12
|
-
jaxsim/api/joint.py,sha256=
|
12
|
+
jaxsim/api/joint.py,sha256=iz7kHLLXMjlDOjKN0T6tcutWCnpnFAOA2IEE9GuxlQI,7304
|
13
13
|
jaxsim/api/kin_dyn_parameters.py,sha256=kbDN5n9uj8CamVJXk1U5oYLbxyjaWDIeUG0V68DCEFs,29578
|
14
14
|
jaxsim/api/link.py,sha256=LAA6ZMQXkWomXeptURBtc7z3_xDZ2BBnBMhVrohh0bE,18621
|
15
15
|
jaxsim/api/model.py,sha256=dpQZDT0BodMfK1wmpG-STFh-rFsJStobQ1fhrWILK9o,73410
|
16
|
-
jaxsim/api/ode.py,sha256=
|
16
|
+
jaxsim/api/ode.py,sha256=_t18avoCJngQk6eMFTGpaeahbpchQP20qJnUOCPkz8s,15360
|
17
17
|
jaxsim/api/ode_data.py,sha256=1SD-x-lYk_YSEnVpxTLd69uOKC0mFUj44ZqpSmEDOxw,20190
|
18
18
|
jaxsim/api/references.py,sha256=fW77LitZ8DYgT6ZmUInJfm5luBV1mTcqcNRiC_i79og,20862
|
19
19
|
jaxsim/integrators/__init__.py,sha256=hxvOD-VK_mmd6v31wtC-nb28AYve1gLuZCNLV9wS-Kg,103
|
@@ -26,7 +26,7 @@ jaxsim/math/cross.py,sha256=U7yEx_l75mSy5g6O-jsjBztApvxC3WaV4MpkS5tThu4,1330
|
|
26
26
|
jaxsim/math/inertia.py,sha256=01hz6wMFreN2jBA0rVoBS1YMVh77KvwuzXSOpI3pxNk,1614
|
27
27
|
jaxsim/math/joint_model.py,sha256=EzAveaG5B6ZnCFNUzN30KEQUVesd83lfWXJarYR-kUw,9989
|
28
28
|
jaxsim/math/quaternion.py,sha256=_WA7W3iv7px83sWO1V1n0-J78hqAlO4SL1-jofE-UZ4,4754
|
29
|
-
jaxsim/math/rotation.py,sha256=
|
29
|
+
jaxsim/math/rotation.py,sha256=P34sx28Rh1MhNwxUxqXjxP-ZN1_5tvoflMoAIpy2LbE,2586
|
30
30
|
jaxsim/math/skew.py,sha256=oOGSSR8PUGROl6IJFlrmu6K3gPH-u16hUPfKIkcVv9o,1177
|
31
31
|
jaxsim/math/transform.py,sha256=KXzQgOnCfAtbXCwxhplpJ3F0JT3oEyeLVby1_uRAryQ,2892
|
32
32
|
jaxsim/mujoco/__init__.py,sha256=fZyRWre49pIhOrYdf6yJk_hOax8qWGe8OCmoq-dMVq8,201
|
@@ -43,7 +43,7 @@ jaxsim/parsers/descriptions/joint.py,sha256=VSb6C0FBBKMqwrHBKfc-Bbn4rl_J0RzUxMQl
|
|
43
43
|
jaxsim/parsers/descriptions/link.py,sha256=Eh0W5qL7_Uw0GV-BkNKXhm9Q2dRTfIWCX5D-87zQkxA,3711
|
44
44
|
jaxsim/parsers/descriptions/model.py,sha256=I2Vsbv8Josl4Le7b5rIvhqA2k9Bbv5JxMqwytayxds0,9833
|
45
45
|
jaxsim/parsers/rod/__init__.py,sha256=G2vqlLajBLUc4gyzXwsEI2Wsi4TMOIF9bLDFeT6KrGU,92
|
46
|
-
jaxsim/parsers/rod/parser.py,sha256=
|
46
|
+
jaxsim/parsers/rod/parser.py,sha256=P3QFPdI2NBxL4TALcPhL6Exij9-Q9W716Aps2cb8s2I,14041
|
47
47
|
jaxsim/parsers/rod/utils.py,sha256=5DsF3OeePZGidOJ5GiFSZx-51uIdnFvMW9EK6SgOW6Q,5698
|
48
48
|
jaxsim/rbda/__init__.py,sha256=kmy4G9aMkrqPNGdLSaSV3k15dpF52vBEUQXDFDuKIxU,337
|
49
49
|
jaxsim/rbda/aba.py,sha256=w7ciyxB0IsmueatT0C7PcBQEl9dyiH9oqJgIi3xeTUE,8983
|
@@ -65,8 +65,8 @@ jaxsim/utils/__init__.py,sha256=Y5zyoRevl3EMVQadhZ4EtSwTEkDt2vcnFoRhPJjKTZ0,215
|
|
65
65
|
jaxsim/utils/jaxsim_dataclass.py,sha256=TGmTQV2Lq7Q-2nLoAEaeNtkPa_qj0IKkdBm4COj46Os,11312
|
66
66
|
jaxsim/utils/tracing.py,sha256=KDMoyVPlu2NJvFkhtZwq5AkqMMgajt3munvJom-vEjQ,650
|
67
67
|
jaxsim/utils/wrappers.py,sha256=Fh82ZcaFi5fUnByyFLnmumaobsu1hJIvFdopUVzJ1ps,4052
|
68
|
-
jaxsim-0.4.3.
|
69
|
-
jaxsim-0.4.3.
|
70
|
-
jaxsim-0.4.3.
|
71
|
-
jaxsim-0.4.3.
|
72
|
-
jaxsim-0.4.3.
|
68
|
+
jaxsim-0.4.3.dev282.dist-info/LICENSE,sha256=eaYdFmdeMbiIoIiPzEK0MjP1S9wtFXjXNR5er49uLR0,1546
|
69
|
+
jaxsim-0.4.3.dev282.dist-info/METADATA,sha256=Llp_WIbsROSnrBpSMJUdFnAOOkLDobo5f87CO8xvOuA,17276
|
70
|
+
jaxsim-0.4.3.dev282.dist-info/WHEEL,sha256=P9jw-gEje8ByB7_hXoICnHtVCrEwMQh-630tKvQWehc,91
|
71
|
+
jaxsim-0.4.3.dev282.dist-info/top_level.txt,sha256=LxGMA8FLtXjQ6oI7N5gd_R_oSUHxpXxUEOfT1xS_ni0,7
|
72
|
+
jaxsim-0.4.3.dev282.dist-info/RECORD,,
|
File without changes
|
File without changes
|
File without changes
|