jaxsim 0.2.dev108__py3-none-any.whl → 0.2.dev166__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/__init__.py +1 -0
- jaxsim/api/contact.py +194 -0
- jaxsim/api/data.py +951 -0
- jaxsim/api/joint.py +148 -0
- jaxsim/api/link.py +262 -0
- jaxsim/api/model.py +1099 -0
- jaxsim/api/ode.py +280 -0
- jaxsim/integrators/__init__.py +2 -0
- jaxsim/integrators/common.py +508 -0
- jaxsim/integrators/fixed_step.py +158 -0
- jaxsim/physics/algos/soft_contacts.py +97 -28
- jaxsim/physics/model/physics_model.py +30 -0
- jaxsim/physics/model/physics_model_state.py +110 -11
- jaxsim/simulation/ode_data.py +43 -0
- {jaxsim-0.2.dev108.dist-info → jaxsim-0.2.dev166.dist-info}/METADATA +2 -1
- {jaxsim-0.2.dev108.dist-info → jaxsim-0.2.dev166.dist-info}/RECORD +20 -10
- {jaxsim-0.2.dev108.dist-info → jaxsim-0.2.dev166.dist-info}/LICENSE +0 -0
- {jaxsim-0.2.dev108.dist-info → jaxsim-0.2.dev166.dist-info}/WHEEL +0 -0
- {jaxsim-0.2.dev108.dist-info → jaxsim-0.2.dev166.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.
|
16
|
-
__version_tuple__ = version_tuple = (0, 2, '
|
15
|
+
__version__ = version = '0.2.dev166'
|
16
|
+
__version_tuple__ = version_tuple = (0, 2, 'dev166')
|
jaxsim/api/__init__.py
ADDED
@@ -0,0 +1 @@
|
|
1
|
+
from . import contact, data, joint, link, model, ode
|
jaxsim/api/contact.py
ADDED
@@ -0,0 +1,194 @@
|
|
1
|
+
import functools
|
2
|
+
|
3
|
+
import jax
|
4
|
+
import jax.numpy as jnp
|
5
|
+
|
6
|
+
import jaxsim.typing as jtp
|
7
|
+
from jaxsim.physics.algos import soft_contacts
|
8
|
+
|
9
|
+
from . import data as Data
|
10
|
+
from . import model as Model
|
11
|
+
|
12
|
+
|
13
|
+
@jax.jit
|
14
|
+
def collidable_point_kinematics(
|
15
|
+
model: Model.JaxSimModel, data: Data.JaxSimModelData
|
16
|
+
) -> tuple[jtp.Matrix, jtp.Matrix]:
|
17
|
+
"""
|
18
|
+
Compute the position and 3D velocity of the collidable points in the world frame.
|
19
|
+
|
20
|
+
Args:
|
21
|
+
model: The model to consider.
|
22
|
+
data: The data of the considered model.
|
23
|
+
|
24
|
+
Returns:
|
25
|
+
The position and velocity of the collidable points in the world frame.
|
26
|
+
|
27
|
+
Note:
|
28
|
+
The collidable point velocity is the plain coordinate derivative of the position.
|
29
|
+
If we attach a frame C = (p_C, [C]) to the collidable point, it corresponds to
|
30
|
+
the linear component of the mixed 6D frame velocity.
|
31
|
+
"""
|
32
|
+
|
33
|
+
from jaxsim.physics.algos.soft_contacts import collidable_points_pos_vel
|
34
|
+
|
35
|
+
W_p_Ci, W_ṗ_Ci = collidable_points_pos_vel(
|
36
|
+
model=model.physics_model,
|
37
|
+
q=data.state.physics_model.joint_positions,
|
38
|
+
qd=data.state.physics_model.joint_velocities,
|
39
|
+
xfb=data.state.physics_model.xfb(),
|
40
|
+
)
|
41
|
+
|
42
|
+
return W_p_Ci.T, W_ṗ_Ci.T
|
43
|
+
|
44
|
+
|
45
|
+
@jax.jit
|
46
|
+
def collidable_point_positions(
|
47
|
+
model: Model.JaxSimModel, data: Data.JaxSimModelData
|
48
|
+
) -> jtp.Matrix:
|
49
|
+
"""
|
50
|
+
Compute the position of the collidable points in the world frame.
|
51
|
+
|
52
|
+
Args:
|
53
|
+
model: The model to consider.
|
54
|
+
data: The data of the considered model.
|
55
|
+
|
56
|
+
Returns:
|
57
|
+
The position of the collidable points in the world frame.
|
58
|
+
"""
|
59
|
+
|
60
|
+
return collidable_point_kinematics(model=model, data=data)[0]
|
61
|
+
|
62
|
+
|
63
|
+
@jax.jit
|
64
|
+
def collidable_point_velocities(
|
65
|
+
model: Model.JaxSimModel, data: Data.JaxSimModelData
|
66
|
+
) -> jtp.Matrix:
|
67
|
+
"""
|
68
|
+
Compute the 3D velocity of the collidable points in the world frame.
|
69
|
+
|
70
|
+
Args:
|
71
|
+
model: The model to consider.
|
72
|
+
data: The data of the considered model.
|
73
|
+
|
74
|
+
Returns:
|
75
|
+
The 3D velocity of the collidable points.
|
76
|
+
"""
|
77
|
+
|
78
|
+
return collidable_point_kinematics(model=model, data=data)[1]
|
79
|
+
|
80
|
+
|
81
|
+
@functools.partial(jax.jit, static_argnames=["link_names"])
|
82
|
+
def in_contact(
|
83
|
+
model: Model.JaxSimModel,
|
84
|
+
data: Data.JaxSimModelData,
|
85
|
+
*,
|
86
|
+
link_names: tuple[str, ...] | None = None,
|
87
|
+
) -> jtp.Vector:
|
88
|
+
"""
|
89
|
+
Return whether the links are in contact with the terrain.
|
90
|
+
|
91
|
+
Args:
|
92
|
+
model: The model to consider.
|
93
|
+
data: The data of the considered model.
|
94
|
+
link_names:
|
95
|
+
The names of the links to consider. If None, all links are considered.
|
96
|
+
|
97
|
+
Returns:
|
98
|
+
A boolean vector indicating whether the links are in contact with the terrain.
|
99
|
+
"""
|
100
|
+
|
101
|
+
link_names = link_names if link_names is not None else model.link_names()
|
102
|
+
|
103
|
+
if set(link_names) - set(model.link_names()) != set():
|
104
|
+
raise ValueError("One or more link names are not part of the model")
|
105
|
+
|
106
|
+
from jaxsim.physics.algos.soft_contacts import collidable_points_pos_vel
|
107
|
+
|
108
|
+
W_p_Ci, _ = collidable_points_pos_vel(
|
109
|
+
model=model.physics_model,
|
110
|
+
q=data.state.physics_model.joint_positions,
|
111
|
+
qd=data.state.physics_model.joint_velocities,
|
112
|
+
xfb=data.state.physics_model.xfb(),
|
113
|
+
)
|
114
|
+
|
115
|
+
terrain_height = jax.vmap(lambda x, y: model.terrain.height(x=x, y=y))(
|
116
|
+
W_p_Ci[0, :], W_p_Ci[1, :]
|
117
|
+
)
|
118
|
+
|
119
|
+
below_terrain = W_p_Ci[2, :] <= terrain_height
|
120
|
+
|
121
|
+
links_in_contact = jax.vmap(
|
122
|
+
lambda link_index: jnp.where(
|
123
|
+
model.physics_model.gc.body == link_index,
|
124
|
+
below_terrain,
|
125
|
+
jnp.zeros_like(below_terrain, dtype=bool),
|
126
|
+
).any()
|
127
|
+
)(jnp.arange(model.number_of_links()))
|
128
|
+
|
129
|
+
return links_in_contact
|
130
|
+
|
131
|
+
|
132
|
+
@jax.jit
|
133
|
+
def estimate_good_soft_contacts_parameters(
|
134
|
+
model: Model.JaxSimModel,
|
135
|
+
static_friction_coefficient: jtp.FloatLike = 0.5,
|
136
|
+
number_of_active_collidable_points_steady_state: jtp.IntLike = 1,
|
137
|
+
damping_ratio: jtp.FloatLike = 1.0,
|
138
|
+
max_penetration: jtp.FloatLike | None = None,
|
139
|
+
) -> soft_contacts.SoftContactsParams:
|
140
|
+
"""
|
141
|
+
Estimate good soft contacts parameters for the given model.
|
142
|
+
|
143
|
+
Args:
|
144
|
+
model: The model to consider.
|
145
|
+
static_friction_coefficient: The static friction coefficient.
|
146
|
+
number_of_active_collidable_points_steady_state:
|
147
|
+
The number of active collidable points in steady state supporting
|
148
|
+
the weight of the robot.
|
149
|
+
damping_ratio: The damping ratio.
|
150
|
+
max_penetration:
|
151
|
+
The maximum penetration allowed in steady state when the robot is
|
152
|
+
supported by the configured number of active collidable points.
|
153
|
+
|
154
|
+
Returns:
|
155
|
+
The estimated good soft contacts parameters.
|
156
|
+
|
157
|
+
Note:
|
158
|
+
This method provides a good starting point for the soft contacts parameters.
|
159
|
+
The user is encouraged to fine-tune the parameters based on the
|
160
|
+
specific application.
|
161
|
+
"""
|
162
|
+
|
163
|
+
def estimate_model_height(model: Model.JaxSimModel) -> jtp.Float:
|
164
|
+
""""""
|
165
|
+
|
166
|
+
zero_data = Data.JaxSimModelData.build(
|
167
|
+
model=model, soft_contacts_params=soft_contacts.SoftContactsParams()
|
168
|
+
)
|
169
|
+
|
170
|
+
W_p_CoM = Model.com_position(model=model, data=zero_data)
|
171
|
+
|
172
|
+
if model.physics_model.is_floating_base:
|
173
|
+
W_pz_C = collidable_point_positions(model=model, data=zero_data)[:, -1]
|
174
|
+
return 2 * (W_p_CoM[2] - W_pz_C.min())
|
175
|
+
|
176
|
+
return 2 * W_p_CoM
|
177
|
+
|
178
|
+
max_δ = (
|
179
|
+
max_penetration
|
180
|
+
if max_penetration is not None
|
181
|
+
else 0.005 * estimate_model_height(model=model)
|
182
|
+
)
|
183
|
+
|
184
|
+
nc = number_of_active_collidable_points_steady_state
|
185
|
+
|
186
|
+
sc_parameters = soft_contacts.SoftContactsParams.build_default_from_physics_model(
|
187
|
+
physics_model=model.physics_model,
|
188
|
+
static_friction_coefficient=static_friction_coefficient,
|
189
|
+
max_penetration=max_δ,
|
190
|
+
number_of_active_collidable_points_steady_state=nc,
|
191
|
+
damping_ratio=damping_ratio,
|
192
|
+
)
|
193
|
+
|
194
|
+
return sc_parameters
|