warp-lang 0.15.0__py3-none-manylinux2014_x86_64.whl → 1.0.0__py3-none-manylinux2014_x86_64.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.
Potentially problematic release.
This version of warp-lang might be problematic. Click here for more details.
- warp/__init__.py +1 -0
- warp/codegen.py +7 -3
- warp/config.py +2 -1
- warp/constants.py +3 -0
- warp/context.py +44 -21
- warp/examples/assets/bunny.usd +0 -0
- warp/examples/assets/cartpole.urdf +110 -0
- warp/examples/assets/crazyflie.usd +0 -0
- warp/examples/assets/cube.usda +42 -0
- warp/examples/assets/nv_ant.xml +92 -0
- warp/examples/assets/nv_humanoid.xml +183 -0
- warp/examples/assets/quadruped.urdf +268 -0
- warp/examples/assets/rocks.nvdb +0 -0
- warp/examples/assets/rocks.usd +0 -0
- warp/examples/assets/sphere.usda +56 -0
- warp/examples/assets/torus.usda +105 -0
- warp/examples/core/example_dem.py +6 -6
- warp/examples/core/example_fluid.py +3 -3
- warp/examples/core/example_graph_capture.py +3 -6
- warp/examples/optim/example_bounce.py +9 -8
- warp/examples/optim/example_cloth_throw.py +12 -8
- warp/examples/optim/example_diffray.py +10 -12
- warp/examples/optim/example_drone.py +31 -14
- warp/examples/optim/example_spring_cage.py +10 -15
- warp/examples/optim/example_trajectory.py +7 -24
- warp/examples/sim/example_cartpole.py +3 -9
- warp/examples/sim/example_cloth.py +10 -10
- warp/examples/sim/example_granular.py +3 -3
- warp/examples/sim/example_granular_collision_sdf.py +9 -4
- warp/examples/sim/example_jacobian_ik.py +0 -10
- warp/examples/sim/example_particle_chain.py +4 -4
- warp/examples/sim/example_quadruped.py +15 -11
- warp/examples/sim/example_rigid_chain.py +13 -8
- warp/examples/sim/example_rigid_contact.py +4 -4
- warp/examples/sim/example_rigid_force.py +7 -7
- warp/examples/sim/example_rigid_soft_contact.py +4 -4
- warp/examples/sim/example_soft_body.py +3 -3
- warp/jax.py +45 -0
- warp/jax_experimental.py +339 -0
- warp/render/render_opengl.py +188 -95
- warp/render/render_usd.py +34 -10
- warp/sim/__init__.py +13 -4
- warp/sim/articulation.py +4 -5
- warp/sim/collide.py +320 -175
- warp/sim/import_mjcf.py +25 -30
- warp/sim/import_urdf.py +94 -63
- warp/sim/import_usd.py +51 -36
- warp/sim/inertia.py +3 -2
- warp/sim/integrator.py +233 -0
- warp/sim/integrator_euler.py +447 -469
- warp/sim/integrator_featherstone.py +1991 -0
- warp/sim/integrator_xpbd.py +1420 -640
- warp/sim/model.py +741 -487
- warp/sim/particles.py +2 -1
- warp/sim/render.py +18 -2
- warp/sim/utils.py +222 -11
- warp/stubs.py +1 -0
- warp/tape.py +6 -9
- warp/tests/test_examples.py +87 -20
- warp/tests/test_grad_customs.py +122 -0
- warp/tests/test_jax.py +254 -0
- warp/tests/test_options.py +13 -53
- warp/tests/test_quat.py +23 -0
- warp/tests/test_snippet.py +2 -0
- warp/tests/test_utils.py +31 -26
- warp/tests/test_verify_fp.py +65 -0
- warp/tests/unittest_suites.py +4 -0
- warp/utils.py +50 -1
- {warp_lang-0.15.0.dist-info → warp_lang-1.0.0.dist-info}/METADATA +1 -1
- {warp_lang-0.15.0.dist-info → warp_lang-1.0.0.dist-info}/RECORD +73 -64
- warp/examples/env/__init__.py +0 -0
- warp/examples/env/env_ant.py +0 -61
- warp/examples/env/env_cartpole.py +0 -63
- warp/examples/env/env_humanoid.py +0 -65
- warp/examples/env/env_usd.py +0 -97
- warp/examples/env/environment.py +0 -526
- warp/sim/optimizer.py +0 -138
- {warp_lang-0.15.0.dist-info → warp_lang-1.0.0.dist-info}/LICENSE.md +0 -0
- {warp_lang-0.15.0.dist-info → warp_lang-1.0.0.dist-info}/WHEEL +0 -0
- {warp_lang-0.15.0.dist-info → warp_lang-1.0.0.dist-info}/top_level.txt +0 -0
warp/sim/model.py
CHANGED
|
@@ -57,8 +57,8 @@ JOINT_UNIVERSAL = wp.constant(6)
|
|
|
57
57
|
JOINT_DISTANCE = wp.constant(7)
|
|
58
58
|
JOINT_D6 = wp.constant(8)
|
|
59
59
|
|
|
60
|
-
# Joint axis mode types
|
|
61
|
-
|
|
60
|
+
# Joint axis control mode types
|
|
61
|
+
JOINT_MODE_FORCE = wp.constant(0)
|
|
62
62
|
JOINT_MODE_TARGET_POSITION = wp.constant(1)
|
|
63
63
|
JOINT_MODE_TARGET_VELOCITY = wp.constant(2)
|
|
64
64
|
|
|
@@ -73,9 +73,12 @@ def flag_to_int(flag):
|
|
|
73
73
|
# Material properties pertaining to rigid shape contact dynamics
|
|
74
74
|
@wp.struct
|
|
75
75
|
class ModelShapeMaterials:
|
|
76
|
-
ke: wp.array(dtype=float) # The contact elastic stiffness (only used by Euler
|
|
77
|
-
kd: wp.array(dtype=float) # The contact damping stiffness (only used by Euler
|
|
78
|
-
kf: wp.array(dtype=float) # The contact friction stiffness (only used by Euler
|
|
76
|
+
ke: wp.array(dtype=float) # The contact elastic stiffness (only used by the Euler integrators)
|
|
77
|
+
kd: wp.array(dtype=float) # The contact damping stiffness (only used by the Euler integrators)
|
|
78
|
+
kf: wp.array(dtype=float) # The contact friction stiffness (only used by the Euler integrators)
|
|
79
|
+
ka: wp.array(
|
|
80
|
+
dtype=float
|
|
81
|
+
) # The contact adhesion distance (values greater than 0 mean adhesive contact; only used by the Euler integrators)
|
|
79
82
|
mu: wp.array(dtype=float) # The coefficient of friction
|
|
80
83
|
restitution: wp.array(dtype=float) # The coefficient of restitution (only used by XPBD integrator)
|
|
81
84
|
|
|
@@ -100,11 +103,11 @@ class JointAxis:
|
|
|
100
103
|
Attributes:
|
|
101
104
|
|
|
102
105
|
axis (3D vector or JointAxis): The 3D axis that this JointAxis object describes, or alternatively another JointAxis object to copy from
|
|
103
|
-
limit_lower (float): The lower limit of the joint axis
|
|
104
|
-
limit_upper (float): The upper limit of the joint axis
|
|
105
|
-
limit_ke (float): The elastic stiffness of the joint axis limits, only respected by :class:`SemiImplicitIntegrator`
|
|
106
|
-
limit_kd (float): The damping stiffness of the joint axis limits, only respected by :class:`SemiImplicitIntegrator`
|
|
107
|
-
|
|
106
|
+
limit_lower (float): The lower position limit of the joint axis
|
|
107
|
+
limit_upper (float): The upper position limit of the joint axis
|
|
108
|
+
limit_ke (float): The elastic stiffness of the joint axis limits, only respected by :class:`SemiImplicitIntegrator` and :class:`FeatherstoneIntegrator`
|
|
109
|
+
limit_kd (float): The damping stiffness of the joint axis limits, only respected by :class:`SemiImplicitIntegrator` and :class:`FeatherstoneIntegrator`
|
|
110
|
+
action (float): The force applied by default to this joint axis, or the target position or velocity (depending on the mode, see `Joint modes`_) of the joint axis
|
|
108
111
|
target_ke (float): The proportional gain of the joint axis target drive PD controller
|
|
109
112
|
target_kd (float): The derivative gain of the joint axis target drive PD controller
|
|
110
113
|
mode (int): The mode of the joint axis, see `Joint modes`_
|
|
@@ -117,10 +120,10 @@ class JointAxis:
|
|
|
117
120
|
limit_upper=math.inf,
|
|
118
121
|
limit_ke=100.0,
|
|
119
122
|
limit_kd=10.0,
|
|
120
|
-
|
|
123
|
+
action=None,
|
|
121
124
|
target_ke=0.0,
|
|
122
125
|
target_kd=0.0,
|
|
123
|
-
mode=
|
|
126
|
+
mode=JOINT_MODE_FORCE,
|
|
124
127
|
):
|
|
125
128
|
if isinstance(axis, JointAxis):
|
|
126
129
|
self.axis = axis.axis
|
|
@@ -128,7 +131,7 @@ class JointAxis:
|
|
|
128
131
|
self.limit_upper = axis.limit_upper
|
|
129
132
|
self.limit_ke = axis.limit_ke
|
|
130
133
|
self.limit_kd = axis.limit_kd
|
|
131
|
-
self.
|
|
134
|
+
self.action = axis.action
|
|
132
135
|
self.target_ke = axis.target_ke
|
|
133
136
|
self.target_kd = axis.target_kd
|
|
134
137
|
self.mode = axis.mode
|
|
@@ -138,12 +141,12 @@ class JointAxis:
|
|
|
138
141
|
self.limit_upper = limit_upper
|
|
139
142
|
self.limit_ke = limit_ke
|
|
140
143
|
self.limit_kd = limit_kd
|
|
141
|
-
if
|
|
142
|
-
self.
|
|
143
|
-
elif limit_lower > 0.0 or limit_upper < 0.0:
|
|
144
|
-
self.
|
|
144
|
+
if action is not None:
|
|
145
|
+
self.action = action
|
|
146
|
+
elif mode == JOINT_MODE_TARGET_POSITION and (limit_lower > 0.0 or limit_upper < 0.0):
|
|
147
|
+
self.action = 0.5 * (limit_lower + limit_upper)
|
|
145
148
|
else:
|
|
146
|
-
self.
|
|
149
|
+
self.action = 0.0
|
|
147
150
|
self.target_ke = target_ke
|
|
148
151
|
self.target_kd = target_kd
|
|
149
152
|
self.mode = mode
|
|
@@ -151,7 +154,7 @@ class JointAxis:
|
|
|
151
154
|
|
|
152
155
|
class SDF:
|
|
153
156
|
"""Describes a signed distance field for simulation
|
|
154
|
-
|
|
157
|
+
|
|
155
158
|
Attributes:
|
|
156
159
|
|
|
157
160
|
volume (Volume): The volume defining the SDF
|
|
@@ -159,6 +162,7 @@ class SDF:
|
|
|
159
162
|
mass (float): The total mass of the SDF
|
|
160
163
|
com (Vec3): The center of mass of the SDF
|
|
161
164
|
"""
|
|
165
|
+
|
|
162
166
|
def __init__(self, volume=None, I=wp.mat33(np.eye(3)), mass=1.0, com=wp.vec3()):
|
|
163
167
|
self.volume = volume
|
|
164
168
|
self.I = I
|
|
@@ -178,30 +182,23 @@ class SDF:
|
|
|
178
182
|
|
|
179
183
|
class Mesh:
|
|
180
184
|
"""Describes a triangle collision mesh for simulation
|
|
181
|
-
|
|
185
|
+
|
|
182
186
|
Example mesh creation from a triangle OBJ mesh file:
|
|
183
187
|
====================================================
|
|
184
188
|
|
|
189
|
+
See :func:`load_mesh` which is provided as a utility function.
|
|
190
|
+
|
|
185
191
|
.. code-block:: python
|
|
186
192
|
|
|
187
193
|
import numpy as np
|
|
188
194
|
import warp as wp
|
|
189
195
|
import warp.sim
|
|
196
|
+
import openmesh
|
|
190
197
|
|
|
191
|
-
|
|
192
|
-
|
|
193
|
-
|
|
194
|
-
|
|
195
|
-
mesh_points = np.array(m.points)
|
|
196
|
-
mesh_indices = np.array(m.cells[0].data, dtype=np.int32).flatten()
|
|
197
|
-
else:
|
|
198
|
-
import openmesh
|
|
199
|
-
m = openmesh.read_trimesh(filename)
|
|
200
|
-
mesh_points = np.array(m.points())
|
|
201
|
-
mesh_indices = np.array(m.face_vertex_indices(), dtype=np.int32).flatten()
|
|
202
|
-
return wp.sim.Mesh(mesh_points, mesh_indices)
|
|
203
|
-
|
|
204
|
-
mesh = load_mesh("mesh.obj")
|
|
198
|
+
m = openmesh.read_trimesh("mesh.obj")
|
|
199
|
+
mesh_points = np.array(m.points())
|
|
200
|
+
mesh_indices = np.array(m.face_vertex_indices(), dtype=np.int32).flatten()
|
|
201
|
+
mesh = wp.sim.Mesh(mesh_points, mesh_indices)
|
|
205
202
|
|
|
206
203
|
Attributes:
|
|
207
204
|
|
|
@@ -238,10 +235,11 @@ class Mesh:
|
|
|
238
235
|
self.mass = 1.0
|
|
239
236
|
self.com = wp.vec3()
|
|
240
237
|
|
|
238
|
+
# construct simulation ready buffers from points
|
|
241
239
|
def finalize(self, device=None):
|
|
242
240
|
"""
|
|
243
241
|
Constructs a simulation-ready :class:`Mesh` object from the mesh data and returns its ID.
|
|
244
|
-
|
|
242
|
+
|
|
245
243
|
Args:
|
|
246
244
|
device: The device on which to allocate the mesh buffers
|
|
247
245
|
|
|
@@ -274,23 +272,24 @@ class State:
|
|
|
274
272
|
|
|
275
273
|
Attributes:
|
|
276
274
|
|
|
277
|
-
|
|
278
|
-
|
|
275
|
+
particle_q (array): Array of 3D particle positions, shape [particle_count], :class:`vec3`
|
|
276
|
+
particle_qd (array): Array of 3D particle velocities, shape [particle_count], :class:`vec3`
|
|
277
|
+
particle_f (array): Array of 3D particle forces, shape [particle_count], :class:`vec3`
|
|
279
278
|
|
|
280
|
-
|
|
281
|
-
|
|
282
|
-
|
|
279
|
+
body_q (array): Array of body coordinates (7-dof transforms) in maximal coordinates, shape [body_count], :class:`transform`
|
|
280
|
+
body_qd (array): Array of body velocities in maximal coordinates (first 3 entries represent angular velocity, last 3 entries represent linear velocity), shape [body_count], :class:`spatial_vector`
|
|
281
|
+
body_f (array): Array of body forces in maximal coordinates (first 3 entries represent torque, last 3 entries represent linear force), shape [body_count], :class:`spatial_vector`
|
|
283
282
|
|
|
284
|
-
|
|
285
|
-
|
|
286
|
-
|
|
283
|
+
Note:
|
|
284
|
+
|
|
285
|
+
:attr:`body_f` represents external wrenches in world frame and denotes wrenches measured w.r.t. to the body's center of mass for all integrators except :class:`FeatherstoneIntegrator` which assumes the wrenches are measured w.r.t. world origin.
|
|
286
|
+
|
|
287
|
+
joint_q (array): Array of generalized joint coordinates, shape [joint_coord_count], float
|
|
288
|
+
joint_qd (array): Array of generalized joint velocities, shape [joint_dof_count], float
|
|
287
289
|
|
|
288
290
|
"""
|
|
289
291
|
|
|
290
292
|
def __init__(self):
|
|
291
|
-
self.particle_count = 0
|
|
292
|
-
self.body_count = 0
|
|
293
|
-
|
|
294
293
|
self.particle_q = None
|
|
295
294
|
self.particle_qd = None
|
|
296
295
|
self.particle_f = None
|
|
@@ -299,31 +298,112 @@ class State:
|
|
|
299
298
|
self.body_qd = None
|
|
300
299
|
self.body_f = None
|
|
301
300
|
|
|
301
|
+
self.joint_q = None
|
|
302
|
+
self.joint_qd = None
|
|
303
|
+
|
|
302
304
|
def clear_forces(self):
|
|
303
|
-
|
|
304
|
-
|
|
305
|
+
"""Clears all forces (for particles and bodies) in the state object."""
|
|
306
|
+
with wp.ScopedTimer("clear_forces", False):
|
|
307
|
+
if self.particle_count:
|
|
308
|
+
self.particle_f.zero_()
|
|
305
309
|
|
|
306
|
-
|
|
307
|
-
|
|
310
|
+
if self.body_count:
|
|
311
|
+
self.body_f.zero_()
|
|
308
312
|
|
|
309
|
-
|
|
310
|
-
|
|
311
|
-
|
|
312
|
-
|
|
313
|
-
|
|
314
|
-
|
|
313
|
+
@property
|
|
314
|
+
def requires_grad(self):
|
|
315
|
+
"""Indicates whether the state arrays have gradient computation enabled."""
|
|
316
|
+
if self.particle_q:
|
|
317
|
+
return self.particle_q.requires_grad
|
|
318
|
+
if self.body_q:
|
|
319
|
+
return self.body_q.requires_grad
|
|
320
|
+
return False
|
|
315
321
|
|
|
316
|
-
|
|
322
|
+
@property
|
|
323
|
+
def body_count(self):
|
|
324
|
+
"""The number of bodies represented in the state."""
|
|
325
|
+
if self.body_q is None:
|
|
326
|
+
return 0
|
|
327
|
+
return len(self.body_q)
|
|
317
328
|
|
|
318
|
-
|
|
319
|
-
|
|
320
|
-
|
|
321
|
-
|
|
329
|
+
@property
|
|
330
|
+
def particle_count(self):
|
|
331
|
+
"""The number of particles represented in the state."""
|
|
332
|
+
if self.particle_q is None:
|
|
333
|
+
return 0
|
|
334
|
+
return len(self.particle_q)
|
|
322
335
|
|
|
323
|
-
|
|
336
|
+
@property
|
|
337
|
+
def joint_coord_count(self):
|
|
338
|
+
"""The number of generalized joint position coordinates represented in the state."""
|
|
339
|
+
if self.joint_q is None:
|
|
340
|
+
return 0
|
|
341
|
+
return len(self.joint_q)
|
|
342
|
+
|
|
343
|
+
@property
|
|
344
|
+
def joint_dof_count(self):
|
|
345
|
+
"""The number of generalized joint velocity coordinates represented in the state."""
|
|
346
|
+
if self.joint_qd is None:
|
|
347
|
+
return 0
|
|
348
|
+
return len(self.joint_qd)
|
|
349
|
+
|
|
350
|
+
|
|
351
|
+
class Control:
|
|
352
|
+
"""
|
|
353
|
+
The Control object holds all *time-varying* control data for a model.
|
|
354
|
+
|
|
355
|
+
Time-varying control data includes joint control inputs, muscle activations, and activation forces for triangle and tetrahedral elements.
|
|
356
|
+
|
|
357
|
+
The exact attributes depend on the contents of the model. Control objects should generally be created using the :func:`Model.control()` function.
|
|
358
|
+
|
|
359
|
+
Attributes:
|
|
360
|
+
|
|
361
|
+
joint_act (array): Array of joint control inputs, shape [joint_axis_count], float
|
|
362
|
+
tri_activations (array): Array of triangle element activations, shape [tri_count], float
|
|
363
|
+
tet_activations (array): Array of tetrahedral element activations, shape [tet_count], float
|
|
364
|
+
muscle_activations (array): Array of muscle activations, shape [muscle_count], float
|
|
365
|
+
|
|
366
|
+
"""
|
|
367
|
+
|
|
368
|
+
def __init__(self, model):
|
|
369
|
+
"""
|
|
370
|
+
Args:
|
|
371
|
+
model (Model): The model to use as a reference for the control inputs
|
|
372
|
+
"""
|
|
373
|
+
self.model = model
|
|
374
|
+
self.joint_act = None
|
|
375
|
+
self.tri_activations = None
|
|
376
|
+
self.tet_activations = None
|
|
377
|
+
self.muscle_activations = None
|
|
378
|
+
|
|
379
|
+
def reset(self):
|
|
380
|
+
"""
|
|
381
|
+
Resets the control inputs to their initial state defined in :class:`Model`.
|
|
382
|
+
"""
|
|
383
|
+
if self.joint_act is not None:
|
|
384
|
+
self.joint_act.assign(self.model.joint_act)
|
|
385
|
+
if self.tri_activations is not None:
|
|
386
|
+
self.tri_activations.assign(self.model.tri_activations)
|
|
387
|
+
if self.tet_activations is not None:
|
|
388
|
+
self.tet_activations.assign(self.model.tet_activations)
|
|
389
|
+
if self.muscle_activations is not None:
|
|
390
|
+
self.muscle_activations.assign(self.model.muscle_activations)
|
|
324
391
|
|
|
325
392
|
|
|
326
393
|
def compute_shape_mass(type, scale, src, density, is_solid, thickness):
|
|
394
|
+
"""Computes the mass, center of mass and 3x3 inertia tensor of a shape
|
|
395
|
+
|
|
396
|
+
Args:
|
|
397
|
+
type: The type of shape (GEO_SPHERE, GEO_BOX, etc.)
|
|
398
|
+
scale: The scale of the shape
|
|
399
|
+
src: The source shape (Mesh or SDF)
|
|
400
|
+
density: The density of the shape
|
|
401
|
+
is_solid: Whether the shape is solid or hollow
|
|
402
|
+
thickness: The thickness of the shape (used for collision detection, and inertia computation of hollow shapes)
|
|
403
|
+
|
|
404
|
+
Returns:
|
|
405
|
+
The mass, center of mass and 3x3 inertia tensor of the shape
|
|
406
|
+
"""
|
|
327
407
|
if density == 0.0 or type == GEO_PLANE: # zero density means fixed
|
|
328
408
|
return 0.0, wp.vec3(), wp.mat33()
|
|
329
409
|
|
|
@@ -402,7 +482,7 @@ class Model:
|
|
|
402
482
|
all geometry, constraints, and parameters used to describe the simulation.
|
|
403
483
|
|
|
404
484
|
Attributes:
|
|
405
|
-
requires_grad (float): Indicates whether the model was finalized with gradient computation enabled
|
|
485
|
+
requires_grad (float): Indicates whether the model was finalized (see :meth:`ModelBuilder.finalize`) with gradient computation enabled
|
|
406
486
|
num_envs (int): Number of articulation environments that were added to the ModelBuilder via `add_builder`
|
|
407
487
|
|
|
408
488
|
particle_q (array): Particle positions, shape [particle_count, 3], float
|
|
@@ -422,6 +502,7 @@ class Model:
|
|
|
422
502
|
particle_max_velocity (float): Maximum particle velocity (to prevent instability)
|
|
423
503
|
|
|
424
504
|
shape_transform (array): Rigid shape transforms, shape [shape_count, 7], float
|
|
505
|
+
shape_visible (array): Rigid shape visibility, shape [shape_count], bool
|
|
425
506
|
shape_body (array): Rigid shape body index, shape [shape_count], int
|
|
426
507
|
body_shapes (dict): Mapping from body index to list of attached shape indices
|
|
427
508
|
shape_materials (ModelShapeMaterials): Rigid shape contact materials, shape [shape_count], float
|
|
@@ -456,6 +537,12 @@ class Model:
|
|
|
456
537
|
tet_activations (array): Tetrahedral volumetric activations, shape [tet_count], float
|
|
457
538
|
tet_materials (array): Tetrahedral elastic parameters in form :math:`k_{mu}, k_{lambda}, k_{damp}`, shape [tet_count, 3]
|
|
458
539
|
|
|
540
|
+
muscle_start (array): Start index of the first muscle point per muscle, shape [muscle_count], int
|
|
541
|
+
muscle_params (array): Muscle parameters, shape [muscle_count, 5], float
|
|
542
|
+
muscle_bodies (array): Body indices of the muscle waypoints, int
|
|
543
|
+
muscle_points (array): Local body offset of the muscle waypoints, float
|
|
544
|
+
muscle_activations (array): Muscle activations, shape [muscle_count], float
|
|
545
|
+
|
|
459
546
|
body_q (array): Poses of rigid bodies used for state initialization, shape [body_count, 7], float
|
|
460
547
|
body_qd (array): Velocities of rigid bodies used for state initialization, shape [body_count, 6], float
|
|
461
548
|
body_com (array): Rigid body center of mass (in local frame), shape [body_count, 7], float
|
|
@@ -467,46 +554,70 @@ class Model:
|
|
|
467
554
|
|
|
468
555
|
joint_q (array): Generalized joint positions used for state initialization, shape [joint_coord_count], float
|
|
469
556
|
joint_qd (array): Generalized joint velocities used for state initialization, shape [joint_dof_count], float
|
|
470
|
-
joint_act (array): Generalized joint
|
|
557
|
+
joint_act (array): Generalized joint control inputs, shape [joint_axis_count], float
|
|
471
558
|
joint_type (array): Joint type, shape [joint_count], int
|
|
472
559
|
joint_parent (array): Joint parent body indices, shape [joint_count], int
|
|
473
560
|
joint_child (array): Joint child body indices, shape [joint_count], int
|
|
474
561
|
joint_X_p (array): Joint transform in parent frame, shape [joint_count, 7], float
|
|
475
562
|
joint_X_c (array): Joint mass frame in child frame, shape [joint_count, 7], float
|
|
476
563
|
joint_axis (array): Joint axis in child frame, shape [joint_axis_count, 3], float
|
|
477
|
-
joint_armature (array): Armature for each joint, shape [joint_count], float
|
|
478
|
-
joint_target (array): Joint target position/velocity (depending on joint axis mode), shape [joint_axis_count], float
|
|
564
|
+
joint_armature (array): Armature for each joint axis (only used by :class:`FeatherstoneIntegrator`), shape [joint_count], float
|
|
479
565
|
joint_target_ke (array): Joint stiffness, shape [joint_axis_count], float
|
|
480
566
|
joint_target_kd (array): Joint damping, shape [joint_axis_count], float
|
|
481
567
|
joint_axis_start (array): Start index of the first axis per joint, shape [joint_count], int
|
|
482
568
|
joint_axis_dim (array): Number of linear and angular axes per joint, shape [joint_count, 2], int
|
|
483
|
-
joint_axis_mode (array): Joint axis mode, shape [joint_axis_count], int
|
|
569
|
+
joint_axis_mode (array): Joint axis mode, shape [joint_axis_count], int. See `Joint modes`_.
|
|
484
570
|
joint_linear_compliance (array): Joint linear compliance, shape [joint_count], float
|
|
485
571
|
joint_angular_compliance (array): Joint linear compliance, shape [joint_count], float
|
|
486
|
-
joint_enabled (array):
|
|
572
|
+
joint_enabled (array): Controls which joint is simulated (bodies become disconnected if False), shape [joint_count], int
|
|
573
|
+
|
|
574
|
+
Note:
|
|
575
|
+
|
|
576
|
+
This setting is not supported by :class:`FeatherstoneIntegrator`.
|
|
577
|
+
|
|
487
578
|
joint_limit_lower (array): Joint lower position limits, shape [joint_count], float
|
|
488
579
|
joint_limit_upper (array): Joint upper position limits, shape [joint_count], float
|
|
489
|
-
joint_limit_ke (array): Joint position limit stiffness (used by
|
|
490
|
-
joint_limit_kd (array): Joint position limit damping (used by
|
|
580
|
+
joint_limit_ke (array): Joint position limit stiffness (used by the Euler integrators), shape [joint_count], float
|
|
581
|
+
joint_limit_kd (array): Joint position limit damping (used by the Euler integrators), shape [joint_count], float
|
|
491
582
|
joint_twist_lower (array): Joint lower twist limit, shape [joint_count], float
|
|
492
583
|
joint_twist_upper (array): Joint upper twist limit, shape [joint_count], float
|
|
493
584
|
joint_q_start (array): Start index of the first position coordinate per joint, shape [joint_count], int
|
|
494
585
|
joint_qd_start (array): Start index of the first velocity coordinate per joint, shape [joint_count], int
|
|
495
586
|
articulation_start (array): Articulation start index, shape [articulation_count], int
|
|
496
587
|
joint_name (list): Joint names, shape [joint_count], str
|
|
497
|
-
joint_attach_ke (float): Joint attachment force stiffness (used by SemiImplicitIntegrator)
|
|
498
|
-
joint_attach_kd (float): Joint attachment force damping (used by SemiImplicitIntegrator)
|
|
588
|
+
joint_attach_ke (float): Joint attachment force stiffness (used by :class:`SemiImplicitIntegrator`)
|
|
589
|
+
joint_attach_kd (float): Joint attachment force damping (used by :class:`SemiImplicitIntegrator`)
|
|
499
590
|
|
|
500
591
|
soft_contact_margin (float): Contact margin for generation of soft contacts
|
|
501
|
-
soft_contact_ke (float): Stiffness of soft contacts (used by
|
|
502
|
-
soft_contact_kd (float): Damping of soft contacts (used by
|
|
503
|
-
soft_contact_kf (float): Stiffness of friction force in soft contacts (used by
|
|
592
|
+
soft_contact_ke (float): Stiffness of soft contacts (used by the Euler integrators)
|
|
593
|
+
soft_contact_kd (float): Damping of soft contacts (used by the Euler integrators)
|
|
594
|
+
soft_contact_kf (float): Stiffness of friction force in soft contacts (used by the Euler integrators)
|
|
504
595
|
soft_contact_mu (float): Friction coefficient of soft contacts
|
|
505
|
-
soft_contact_restitution (float): Restitution coefficient of soft contacts (used by XPBDIntegrator)
|
|
506
|
-
|
|
596
|
+
soft_contact_restitution (float): Restitution coefficient of soft contacts (used by :class:`XPBDIntegrator`)
|
|
597
|
+
|
|
598
|
+
soft_contact_count (array): Number of active particle-shape contacts, shape [1], int
|
|
599
|
+
soft_contact_particle (array), Index of particle per soft contact point, shape [soft_contact_max], int
|
|
600
|
+
soft_contact_shape (array), Index of shape per soft contact point, shape [soft_contact_max], int
|
|
601
|
+
soft_contact_body_pos (array), Positional offset of soft contact point in body frame, shape [soft_contact_max], vec3
|
|
602
|
+
soft_contact_body_vel (array), Linear velocity of soft contact point in body frame, shape [soft_contact_max], vec3
|
|
603
|
+
soft_contact_normal (array), Contact surface normal of soft contact point in world space, shape [soft_contact_max], vec3
|
|
604
|
+
|
|
605
|
+
rigid_contact_max (int): Maximum number of potential rigid body contact points to generate ignoring the `rigid_mesh_contact_max` limit.
|
|
606
|
+
rigid_contact_max_limited (int): Maximum number of potential rigid body contact points to generate respecting the `rigid_mesh_contact_max` limit.
|
|
607
|
+
rigid_mesh_contact_max (int): Maximum number of rigid body contact points to generate per mesh (0 = unlimited, default)
|
|
507
608
|
rigid_contact_margin (float): Contact margin for generation of rigid body contacts
|
|
508
|
-
rigid_contact_torsional_friction (float): Torsional friction coefficient for rigid body contacts (used by XPBDIntegrator)
|
|
509
|
-
rigid_contact_rolling_friction (float): Rolling friction coefficient for rigid body contacts (used by XPBDIntegrator)
|
|
609
|
+
rigid_contact_torsional_friction (float): Torsional friction coefficient for rigid body contacts (used by :class:`XPBDIntegrator`)
|
|
610
|
+
rigid_contact_rolling_friction (float): Rolling friction coefficient for rigid body contacts (used by :class:`XPBDIntegrator`)
|
|
611
|
+
|
|
612
|
+
rigid_contact_count (array): Number of active shape-shape contacts, shape [1], int
|
|
613
|
+
rigid_contact_point0 (array): Contact point relative to frame of body 0, shape [rigid_contact_max], vec3
|
|
614
|
+
rigid_contact_point1 (array): Contact point relative to frame of body 1, shape [rigid_contact_max], vec3
|
|
615
|
+
rigid_contact_offset0 (array): Contact offset due to contact thickness relative to body 0, shape [rigid_contact_max], vec3
|
|
616
|
+
rigid_contact_offset1 (array): Contact offset due to contact thickness relative to body 1, shape [rigid_contact_max], vec3
|
|
617
|
+
rigid_contact_normal (array): Contact normal in world space, shape [rigid_contact_max], vec3
|
|
618
|
+
rigid_contact_thickness (array): Total contact thickness, shape [rigid_contact_max], float
|
|
619
|
+
rigid_contact_shape0 (array): Index of shape 0 per contact, shape [rigid_contact_max], int
|
|
620
|
+
rigid_contact_shape1 (array): Index of shape 1 per contact, shape [rigid_contact_max], int
|
|
510
621
|
|
|
511
622
|
ground (bool): Whether the ground plane and ground contacts are enabled
|
|
512
623
|
ground_plane (array): Ground plane 3D normal and offset, shape [4], float
|
|
@@ -544,7 +655,7 @@ class Model:
|
|
|
544
655
|
self.particle_qd = None
|
|
545
656
|
self.particle_mass = None
|
|
546
657
|
self.particle_inv_mass = None
|
|
547
|
-
self.
|
|
658
|
+
self.particle_radius = None
|
|
548
659
|
self.particle_max_radius = 0.0
|
|
549
660
|
self.particle_ke = 1.0e3
|
|
550
661
|
self.particle_kd = 1.0e2
|
|
@@ -558,6 +669,7 @@ class Model:
|
|
|
558
669
|
|
|
559
670
|
self.shape_transform = None
|
|
560
671
|
self.shape_body = None
|
|
672
|
+
self.shape_visible = None
|
|
561
673
|
self.body_shapes = {}
|
|
562
674
|
self.shape_materials = ModelShapeMaterials()
|
|
563
675
|
self.shape_geo = ModelShapeGeometry()
|
|
@@ -576,6 +688,7 @@ class Model:
|
|
|
576
688
|
self.spring_stiffness = None
|
|
577
689
|
self.spring_damping = None
|
|
578
690
|
self.spring_control = None
|
|
691
|
+
self.spring_constraint_lambdas = None
|
|
579
692
|
|
|
580
693
|
self.tri_indices = None
|
|
581
694
|
self.tri_poses = None
|
|
@@ -585,12 +698,19 @@ class Model:
|
|
|
585
698
|
self.edge_indices = None
|
|
586
699
|
self.edge_rest_angle = None
|
|
587
700
|
self.edge_bending_properties = None
|
|
701
|
+
self.edge_constraint_lambdas = None
|
|
588
702
|
|
|
589
703
|
self.tet_indices = None
|
|
590
704
|
self.tet_poses = None
|
|
591
705
|
self.tet_activations = None
|
|
592
706
|
self.tet_materials = None
|
|
593
707
|
|
|
708
|
+
self.muscle_start = None
|
|
709
|
+
self.muscle_params = None
|
|
710
|
+
self.muscle_bodies = None
|
|
711
|
+
self.muscle_points = None
|
|
712
|
+
self.muscle_activations = None
|
|
713
|
+
|
|
594
714
|
self.body_q = None
|
|
595
715
|
self.body_qd = None
|
|
596
716
|
self.body_com = None
|
|
@@ -610,7 +730,6 @@ class Model:
|
|
|
610
730
|
self.joint_X_c = None
|
|
611
731
|
self.joint_axis = None
|
|
612
732
|
self.joint_armature = None
|
|
613
|
-
self.joint_target = None
|
|
614
733
|
self.joint_target_ke = None
|
|
615
734
|
self.joint_target_kd = None
|
|
616
735
|
self.joint_axis_start = None
|
|
@@ -641,16 +760,36 @@ class Model:
|
|
|
641
760
|
self.soft_contact_mu = 0.5
|
|
642
761
|
self.soft_contact_restitution = 0.0
|
|
643
762
|
|
|
763
|
+
self.soft_contact_count = 0
|
|
764
|
+
self.soft_contact_particle = None
|
|
765
|
+
self.soft_contact_shape = None
|
|
766
|
+
self.soft_contact_body_pos = None
|
|
767
|
+
self.soft_contact_body_vel = None
|
|
768
|
+
self.soft_contact_normal = None
|
|
769
|
+
|
|
770
|
+
self.rigid_contact_max = 0
|
|
771
|
+
self.rigid_contact_max_limited = 0
|
|
772
|
+
self.rigid_mesh_contact_max = 0
|
|
644
773
|
self.rigid_contact_margin = None
|
|
645
774
|
self.rigid_contact_torsional_friction = None
|
|
646
775
|
self.rigid_contact_rolling_friction = None
|
|
647
776
|
|
|
777
|
+
self.rigid_contact_count = None
|
|
778
|
+
self.rigid_contact_point0 = None
|
|
779
|
+
self.rigid_contact_point1 = None
|
|
780
|
+
self.rigid_contact_offset0 = None
|
|
781
|
+
self.rigid_contact_offset1 = None
|
|
782
|
+
self.rigid_contact_normal = None
|
|
783
|
+
self.rigid_contact_thickness = None
|
|
784
|
+
self.rigid_contact_shape0 = None
|
|
785
|
+
self.rigid_contact_shape1 = None
|
|
786
|
+
|
|
648
787
|
# toggles ground contact for all shapes
|
|
649
788
|
self.ground = True
|
|
650
789
|
self.ground_plane = None
|
|
651
790
|
self.up_vector = np.array((0.0, 1.0, 0.0))
|
|
652
791
|
self.up_axis = 1
|
|
653
|
-
self.gravity = np.array((0.0, -9.
|
|
792
|
+
self.gravity = np.array((0.0, -9.80665, 0.0))
|
|
654
793
|
|
|
655
794
|
self.particle_count = 0
|
|
656
795
|
self.body_count = 0
|
|
@@ -673,51 +812,80 @@ class Model:
|
|
|
673
812
|
|
|
674
813
|
The returned state will be initialized with the initial configuration given in
|
|
675
814
|
the model description.
|
|
815
|
+
|
|
816
|
+
Args:
|
|
817
|
+
requires_grad (bool): Manual overwrite whether the state variables should have `requires_grad` enabled (defaults to `None` to use the model's setting :attr:`requires_grad`)
|
|
818
|
+
|
|
819
|
+
Returns:
|
|
820
|
+
State: The state object
|
|
676
821
|
"""
|
|
677
822
|
|
|
678
823
|
s = State()
|
|
679
824
|
if requires_grad is None:
|
|
680
825
|
requires_grad = self.requires_grad
|
|
681
826
|
|
|
682
|
-
s.particle_count = self.particle_count
|
|
683
|
-
s.body_count = self.body_count
|
|
684
|
-
|
|
685
|
-
# --------------------------------
|
|
686
|
-
# dynamic state (input, output)
|
|
687
|
-
|
|
688
827
|
# particles
|
|
689
828
|
if self.particle_count:
|
|
690
|
-
s.particle_q = wp.clone(self.particle_q)
|
|
691
|
-
s.particle_qd = wp.clone(self.particle_qd)
|
|
692
|
-
s.particle_f = wp.zeros_like(self.particle_qd)
|
|
693
|
-
|
|
694
|
-
s.particle_q.requires_grad = requires_grad
|
|
695
|
-
s.particle_qd.requires_grad = requires_grad
|
|
696
|
-
s.particle_f.requires_grad = requires_grad
|
|
829
|
+
s.particle_q = wp.clone(self.particle_q, requires_grad=requires_grad)
|
|
830
|
+
s.particle_qd = wp.clone(self.particle_qd, requires_grad=requires_grad)
|
|
831
|
+
s.particle_f = wp.zeros_like(self.particle_qd, requires_grad=requires_grad)
|
|
697
832
|
|
|
698
833
|
# articulations
|
|
699
834
|
if self.body_count:
|
|
700
|
-
s.body_q = wp.clone(self.body_q)
|
|
701
|
-
s.body_qd = wp.clone(self.body_qd)
|
|
702
|
-
s.body_f = wp.zeros_like(self.body_qd)
|
|
835
|
+
s.body_q = wp.clone(self.body_q, requires_grad=requires_grad)
|
|
836
|
+
s.body_qd = wp.clone(self.body_qd, requires_grad=requires_grad)
|
|
837
|
+
s.body_f = wp.zeros_like(self.body_qd, requires_grad=requires_grad)
|
|
703
838
|
|
|
704
|
-
|
|
705
|
-
|
|
706
|
-
)
|
|
707
|
-
|
|
708
|
-
s.body_q.requires_grad = requires_grad
|
|
709
|
-
s.body_qd.requires_grad = requires_grad
|
|
710
|
-
s.body_f.requires_grad = requires_grad
|
|
839
|
+
if self.joint_count:
|
|
840
|
+
s.joint_q = wp.clone(self.joint_q, requires_grad=requires_grad)
|
|
841
|
+
s.joint_qd = wp.clone(self.joint_qd, requires_grad=requires_grad)
|
|
711
842
|
|
|
712
843
|
return s
|
|
713
844
|
|
|
845
|
+
def control(self, requires_grad=None, clone_variables=True) -> Control:
|
|
846
|
+
"""
|
|
847
|
+
Returns a control object for the model.
|
|
848
|
+
|
|
849
|
+
The returned control object will be initialized with the control inputs given in the model description.
|
|
850
|
+
|
|
851
|
+
Args:
|
|
852
|
+
requires_grad (bool): Manual overwrite whether the control variables should have `requires_grad` enabled (defaults to `None` to use the model's setting :attr:`requires_grad`)
|
|
853
|
+
clone_variables (bool): Whether to clone the control inputs or use the original data
|
|
854
|
+
|
|
855
|
+
Returns:
|
|
856
|
+
Control: The control object
|
|
857
|
+
"""
|
|
858
|
+
c = Control(self)
|
|
859
|
+
if requires_grad is None:
|
|
860
|
+
requires_grad = self.requires_grad
|
|
861
|
+
if clone_variables:
|
|
862
|
+
if self.joint_count:
|
|
863
|
+
c.joint_act = wp.clone(self.joint_act, requires_grad=requires_grad)
|
|
864
|
+
if self.tri_count:
|
|
865
|
+
c.tri_activations = wp.clone(self.tri_activations, requires_grad=requires_grad)
|
|
866
|
+
if self.tet_count:
|
|
867
|
+
c.tet_activations = wp.clone(self.tet_activations, requires_grad=requires_grad)
|
|
868
|
+
if self.muscle_count:
|
|
869
|
+
c.muscle_activations = wp.clone(self.muscle_activations, requires_grad=requires_grad)
|
|
870
|
+
else:
|
|
871
|
+
c.joint_act = self.joint_act
|
|
872
|
+
c.tri_activations = self.tri_activations
|
|
873
|
+
c.tet_activations = self.tet_activations
|
|
874
|
+
c.muscle_activations = self.muscle_activations
|
|
875
|
+
return c
|
|
876
|
+
|
|
877
|
+
def _allocate_soft_contacts(self, target, count, requires_grad=False):
|
|
878
|
+
with wp.ScopedDevice(self.device):
|
|
879
|
+
target.soft_contact_count = wp.zeros(1, dtype=wp.int32)
|
|
880
|
+
target.soft_contact_particle = wp.zeros(count, dtype=int)
|
|
881
|
+
target.soft_contact_shape = wp.zeros(count, dtype=int)
|
|
882
|
+
target.soft_contact_body_pos = wp.zeros(count, dtype=wp.vec3, requires_grad=requires_grad)
|
|
883
|
+
target.soft_contact_body_vel = wp.zeros(count, dtype=wp.vec3, requires_grad=requires_grad)
|
|
884
|
+
target.soft_contact_normal = wp.zeros(count, dtype=wp.vec3, requires_grad=requires_grad)
|
|
885
|
+
target.soft_contact_tids = wp.zeros(count, dtype=int)
|
|
886
|
+
|
|
714
887
|
def allocate_soft_contacts(self, count, requires_grad=False):
|
|
715
|
-
self.
|
|
716
|
-
self.soft_contact_particle = wp.zeros(count, dtype=int, device=self.device)
|
|
717
|
-
self.soft_contact_shape = wp.zeros(count, dtype=int, device=self.device)
|
|
718
|
-
self.soft_contact_body_pos = wp.zeros(count, dtype=wp.vec3, device=self.device, requires_grad=requires_grad)
|
|
719
|
-
self.soft_contact_body_vel = wp.zeros(count, dtype=wp.vec3, device=self.device, requires_grad=requires_grad)
|
|
720
|
-
self.soft_contact_normal = wp.zeros(count, dtype=wp.vec3, device=self.device, requires_grad=requires_grad)
|
|
888
|
+
self._allocate_soft_contacts(self, count, requires_grad)
|
|
721
889
|
|
|
722
890
|
def find_shape_contact_pairs(self):
|
|
723
891
|
# find potential contact pairs based on collision groups and collision mask (pairwise filtering)
|
|
@@ -751,18 +919,26 @@ class Model:
|
|
|
751
919
|
|
|
752
920
|
def count_contact_points(self):
|
|
753
921
|
"""
|
|
754
|
-
Counts the maximum number of contact points that need to be allocated.
|
|
922
|
+
Counts the maximum number of rigid contact points that need to be allocated.
|
|
923
|
+
This function returns two values corresponding to the maximum number of potential contacts
|
|
924
|
+
excluding the limiting from `Model.rigid_mesh_contact_max` and the maximum number of
|
|
925
|
+
contact points that may be generated when considering the `Model.rigid_mesh_contact_max` limit.
|
|
926
|
+
|
|
927
|
+
:returns:
|
|
928
|
+
- potential_count (int): Potential number of contact points
|
|
929
|
+
- actual_count (int): Actual number of contact points
|
|
755
930
|
"""
|
|
756
931
|
from .collide import count_contact_points
|
|
757
932
|
|
|
758
933
|
# calculate the potential number of shape pair contact points
|
|
759
|
-
contact_count = wp.zeros(
|
|
934
|
+
contact_count = wp.zeros(2, dtype=wp.int32, device=self.device)
|
|
760
935
|
wp.launch(
|
|
761
936
|
kernel=count_contact_points,
|
|
762
937
|
dim=self.shape_contact_pair_count,
|
|
763
938
|
inputs=[
|
|
764
939
|
self.shape_contact_pairs,
|
|
765
940
|
self.shape_geo,
|
|
941
|
+
self.rigid_mesh_contact_max,
|
|
766
942
|
],
|
|
767
943
|
outputs=[contact_count],
|
|
768
944
|
device=self.device,
|
|
@@ -775,158 +951,77 @@ class Model:
|
|
|
775
951
|
inputs=[
|
|
776
952
|
self.shape_ground_contact_pairs,
|
|
777
953
|
self.shape_geo,
|
|
954
|
+
self.rigid_mesh_contact_max,
|
|
778
955
|
],
|
|
779
956
|
outputs=[contact_count],
|
|
780
957
|
device=self.device,
|
|
781
958
|
record_tape=False,
|
|
782
959
|
)
|
|
783
|
-
|
|
784
|
-
|
|
960
|
+
counts = contact_count.numpy()
|
|
961
|
+
potential_count = int(counts[0])
|
|
962
|
+
actual_count = int(counts[1])
|
|
963
|
+
return potential_count, actual_count
|
|
785
964
|
|
|
786
|
-
def allocate_rigid_contacts(self, count=None, requires_grad=False):
|
|
965
|
+
def allocate_rigid_contacts(self, target=None, count=None, limited_contact_count=None, requires_grad=False):
|
|
787
966
|
if count is not None:
|
|
967
|
+
# potential number of contact points to consider
|
|
788
968
|
self.rigid_contact_max = count
|
|
789
|
-
|
|
790
|
-
|
|
791
|
-
|
|
792
|
-
|
|
793
|
-
|
|
794
|
-
|
|
795
|
-
|
|
796
|
-
|
|
797
|
-
|
|
798
|
-
|
|
799
|
-
|
|
800
|
-
|
|
801
|
-
|
|
802
|
-
|
|
803
|
-
|
|
804
|
-
|
|
805
|
-
|
|
806
|
-
|
|
807
|
-
|
|
808
|
-
|
|
809
|
-
|
|
810
|
-
|
|
811
|
-
|
|
812
|
-
|
|
813
|
-
|
|
814
|
-
|
|
815
|
-
|
|
816
|
-
|
|
817
|
-
|
|
818
|
-
|
|
819
|
-
|
|
820
|
-
|
|
821
|
-
|
|
822
|
-
|
|
823
|
-
|
|
824
|
-
|
|
825
|
-
|
|
826
|
-
|
|
827
|
-
|
|
828
|
-
|
|
829
|
-
|
|
830
|
-
|
|
831
|
-
|
|
832
|
-
|
|
833
|
-
|
|
834
|
-
|
|
835
|
-
|
|
836
|
-
|
|
837
|
-
|
|
838
|
-
|
|
839
|
-
# contact distance before the solver iterations
|
|
840
|
-
self.rigid_active_contact_distance_prev = wp.zeros(
|
|
841
|
-
self.rigid_contact_max, dtype=wp.float32, device=self.device, requires_grad=requires_grad
|
|
842
|
-
)
|
|
843
|
-
# world space position of point0 before the solver iterations
|
|
844
|
-
self.rigid_active_contact_point0_prev = wp.zeros(
|
|
845
|
-
self.rigid_contact_max, dtype=wp.vec3, device=self.device, requires_grad=requires_grad
|
|
846
|
-
)
|
|
847
|
-
# world space position of point1 before the solver iterations
|
|
848
|
-
self.rigid_active_contact_point1_prev = wp.zeros(
|
|
849
|
-
self.rigid_contact_max, dtype=wp.vec3, device=self.device, requires_grad=requires_grad
|
|
850
|
-
)
|
|
851
|
-
# number of contact constraints per rigid body (used for scaling the constraint contributions, a basic version of mass splitting)
|
|
852
|
-
self.rigid_contact_inv_weight = wp.zeros(
|
|
853
|
-
len(self.body_q), dtype=wp.float32, device=self.device, requires_grad=requires_grad
|
|
854
|
-
)
|
|
855
|
-
# number of contact constraints before the solver iterations
|
|
856
|
-
self.rigid_contact_inv_weight_prev = wp.zeros(
|
|
857
|
-
len(self.body_q), dtype=wp.float32, device=self.device, requires_grad=requires_grad
|
|
858
|
-
)
|
|
859
|
-
|
|
860
|
-
def flatten(self):
|
|
861
|
-
"""Returns a list of Tensors stored by the model
|
|
862
|
-
|
|
863
|
-
This function is intended to be used internal-only but can be used to obtain
|
|
864
|
-
a set of all tensors owned by the model.
|
|
865
|
-
"""
|
|
866
|
-
|
|
867
|
-
tensors = []
|
|
868
|
-
|
|
869
|
-
# build a list of all tensor attributes
|
|
870
|
-
for attr, value in self.__dict__.items():
|
|
871
|
-
if wp.is_tensor(value):
|
|
872
|
-
tensors.append(value)
|
|
873
|
-
|
|
874
|
-
return tensors
|
|
875
|
-
|
|
876
|
-
def collide(self, state: State):
|
|
877
|
-
wp.utils.warn(
|
|
878
|
-
"Model.collide() is not needed anymore and will be removed in a future Warp version.",
|
|
879
|
-
DeprecationWarning,
|
|
880
|
-
stacklevel=2,
|
|
881
|
-
)
|
|
969
|
+
if limited_contact_count is not None:
|
|
970
|
+
self.rigid_contact_max_limited = limited_contact_count
|
|
971
|
+
if target is None:
|
|
972
|
+
target = self
|
|
973
|
+
|
|
974
|
+
with wp.ScopedDevice(self.device):
|
|
975
|
+
# serves as counter of the number of active contact points
|
|
976
|
+
target.rigid_contact_count = wp.zeros(1, dtype=wp.int32)
|
|
977
|
+
# contact point ID within the (shape_a, shape_b) contact pair
|
|
978
|
+
target.rigid_contact_point_id = wp.zeros(self.rigid_contact_max, dtype=wp.int32)
|
|
979
|
+
# position of contact point in body 0's frame before the integration step
|
|
980
|
+
target.rigid_contact_point0 = wp.zeros(
|
|
981
|
+
self.rigid_contact_max_limited, dtype=wp.vec3, requires_grad=requires_grad
|
|
982
|
+
)
|
|
983
|
+
# position of contact point in body 1's frame before the integration step
|
|
984
|
+
target.rigid_contact_point1 = wp.zeros(
|
|
985
|
+
self.rigid_contact_max_limited, dtype=wp.vec3, requires_grad=requires_grad
|
|
986
|
+
)
|
|
987
|
+
# moment arm before the integration step resulting from thickness displacement added to contact point 0 in body 0's frame (used in XPBD contact friction handling)
|
|
988
|
+
target.rigid_contact_offset0 = wp.zeros(
|
|
989
|
+
self.rigid_contact_max_limited, dtype=wp.vec3, requires_grad=requires_grad
|
|
990
|
+
)
|
|
991
|
+
# moment arm before the integration step resulting from thickness displacement added to contact point 1 in body 1's frame (used in XPBD contact friction handling)
|
|
992
|
+
target.rigid_contact_offset1 = wp.zeros(
|
|
993
|
+
self.rigid_contact_max_limited, dtype=wp.vec3, requires_grad=requires_grad
|
|
994
|
+
)
|
|
995
|
+
# contact normal in world frame
|
|
996
|
+
target.rigid_contact_normal = wp.zeros(
|
|
997
|
+
self.rigid_contact_max_limited, dtype=wp.vec3, requires_grad=requires_grad
|
|
998
|
+
)
|
|
999
|
+
# combined thickness of both shapes
|
|
1000
|
+
target.rigid_contact_thickness = wp.zeros(
|
|
1001
|
+
self.rigid_contact_max_limited, dtype=wp.float32, requires_grad=requires_grad
|
|
1002
|
+
)
|
|
1003
|
+
# ID of the first shape in the contact pair
|
|
1004
|
+
target.rigid_contact_shape0 = wp.zeros(self.rigid_contact_max_limited, dtype=wp.int32)
|
|
1005
|
+
# ID of the second shape in the contact pair
|
|
1006
|
+
target.rigid_contact_shape1 = wp.zeros(self.rigid_contact_max_limited, dtype=wp.int32)
|
|
1007
|
+
|
|
1008
|
+
# shape IDs of potential contact pairs found during broadphase
|
|
1009
|
+
target.rigid_contact_broad_shape0 = wp.zeros(self.rigid_contact_max, dtype=wp.int32)
|
|
1010
|
+
target.rigid_contact_broad_shape1 = wp.zeros(self.rigid_contact_max, dtype=wp.int32)
|
|
1011
|
+
|
|
1012
|
+
max_pair_count = self.shape_count * self.shape_count
|
|
1013
|
+
# maximum number of contact points per contact pair
|
|
1014
|
+
target.rigid_contact_point_limit = wp.zeros(max_pair_count, dtype=wp.int32)
|
|
1015
|
+
# currently found contacts per contact pair
|
|
1016
|
+
target.rigid_contact_pairwise_counter = wp.zeros(max_pair_count, dtype=wp.int32)
|
|
1017
|
+
# ID of thread that found the current contact point
|
|
1018
|
+
target.rigid_contact_tids = wp.zeros(self.rigid_contact_max, dtype=wp.int32)
|
|
882
1019
|
|
|
883
1020
|
@property
|
|
884
1021
|
def soft_contact_max(self):
|
|
885
1022
|
"""Maximum number of soft contacts that can be registered"""
|
|
886
1023
|
return len(self.soft_contact_particle)
|
|
887
1024
|
|
|
888
|
-
@property
|
|
889
|
-
def soft_contact_distance(self):
|
|
890
|
-
wp.utils.warn(
|
|
891
|
-
"Model.soft_contact_distance is deprecated and will be removed in a future Warp version. "
|
|
892
|
-
"Particles now have individual radii, returning `Model.particle_max_radius`.",
|
|
893
|
-
DeprecationWarning,
|
|
894
|
-
stacklevel=2,
|
|
895
|
-
)
|
|
896
|
-
return self.particle_max_radius
|
|
897
|
-
|
|
898
|
-
@soft_contact_distance.setter
|
|
899
|
-
def soft_contact_distance(self, value):
|
|
900
|
-
wp.utils.warn(
|
|
901
|
-
"Model.soft_contact_distance is deprecated and will be removed in a future Warp version. "
|
|
902
|
-
"Particles now have individual radii, see `Model.particle_radius`.",
|
|
903
|
-
DeprecationWarning,
|
|
904
|
-
stacklevel=2,
|
|
905
|
-
)
|
|
906
|
-
|
|
907
|
-
@property
|
|
908
|
-
def particle_radius(self):
|
|
909
|
-
# Array of per-particle radii
|
|
910
|
-
return self._particle_radius
|
|
911
|
-
|
|
912
|
-
@particle_radius.setter
|
|
913
|
-
def particle_radius(self, value):
|
|
914
|
-
if isinstance(value, float):
|
|
915
|
-
wp.utils.warn(
|
|
916
|
-
"Model.particle_radius is an array of per-particle radii, assigning with a scalar value "
|
|
917
|
-
"is deprecated and will be removed in a future Warp version.",
|
|
918
|
-
PendingDeprecationWarning,
|
|
919
|
-
stacklevel=2,
|
|
920
|
-
)
|
|
921
|
-
self._particle_radius.fill_(value)
|
|
922
|
-
self.particle_max_radius = value
|
|
923
|
-
else:
|
|
924
|
-
self._particle_radius = value
|
|
925
|
-
# TODO implement max radius update to be compatible with graph capture
|
|
926
|
-
device = wp.get_device(self.device)
|
|
927
|
-
if not device.is_capturing:
|
|
928
|
-
self.particle_max_radius = self._particle_radius.numpy().max()
|
|
929
|
-
|
|
930
1025
|
|
|
931
1026
|
class ModelBuilder:
|
|
932
1027
|
"""A helper class for building simulation models at runtime.
|
|
@@ -959,12 +1054,13 @@ class ModelBuilder:
|
|
|
959
1054
|
model = builder.finalize("cuda")
|
|
960
1055
|
|
|
961
1056
|
state = model.state()
|
|
1057
|
+
control = model.control() # optional, to support time-varying control inputs
|
|
962
1058
|
integrator = wp.sim.SemiImplicitIntegrator()
|
|
963
1059
|
|
|
964
1060
|
for i in range(100):
|
|
965
1061
|
|
|
966
1062
|
state.clear_forces()
|
|
967
|
-
integrator.simulate(model, state, state, dt=1.0/60.0)
|
|
1063
|
+
integrator.simulate(model, state, state, dt=1.0/60.0, control=control)
|
|
968
1064
|
|
|
969
1065
|
Note:
|
|
970
1066
|
It is strongly recommended to use the ModelBuilder to construct a simulation rather
|
|
@@ -994,17 +1090,16 @@ class ModelBuilder:
|
|
|
994
1090
|
default_shape_ke = 1.0e5
|
|
995
1091
|
default_shape_kd = 1000.0
|
|
996
1092
|
default_shape_kf = 1000.0
|
|
1093
|
+
default_shape_ka = 0.0
|
|
997
1094
|
default_shape_mu = 0.5
|
|
998
1095
|
default_shape_restitution = 0.0
|
|
999
1096
|
default_shape_density = 1000.0
|
|
1097
|
+
default_shape_thickness = 1e-5
|
|
1000
1098
|
|
|
1001
1099
|
# Default joint settings
|
|
1002
1100
|
default_joint_limit_ke = 100.0
|
|
1003
1101
|
default_joint_limit_kd = 1.0
|
|
1004
1102
|
|
|
1005
|
-
# Default geo settings
|
|
1006
|
-
default_geo_thickness = 1e-5
|
|
1007
|
-
|
|
1008
1103
|
def __init__(self, up_vector=(0.0, 1.0, 0.0), gravity=-9.80665):
|
|
1009
1104
|
self.num_envs = 0
|
|
1010
1105
|
|
|
@@ -1021,6 +1116,7 @@ class ModelBuilder:
|
|
|
1021
1116
|
self.shape_transform = []
|
|
1022
1117
|
# maps from shape index to body index
|
|
1023
1118
|
self.shape_body = []
|
|
1119
|
+
self.shape_visible = []
|
|
1024
1120
|
self.shape_geo_type = []
|
|
1025
1121
|
self.shape_geo_scale = []
|
|
1026
1122
|
self.shape_geo_src = []
|
|
@@ -1029,6 +1125,7 @@ class ModelBuilder:
|
|
|
1029
1125
|
self.shape_material_ke = []
|
|
1030
1126
|
self.shape_material_kd = []
|
|
1031
1127
|
self.shape_material_kf = []
|
|
1128
|
+
self.shape_material_ka = []
|
|
1032
1129
|
self.shape_material_mu = []
|
|
1033
1130
|
self.shape_material_restitution = []
|
|
1034
1131
|
# collision groups within collisions are handled
|
|
@@ -1074,7 +1171,7 @@ class ModelBuilder:
|
|
|
1074
1171
|
# muscles
|
|
1075
1172
|
self.muscle_start = []
|
|
1076
1173
|
self.muscle_params = []
|
|
1077
|
-
self.
|
|
1174
|
+
self.muscle_activations = []
|
|
1078
1175
|
self.muscle_bodies = []
|
|
1079
1176
|
self.muscle_points = []
|
|
1080
1177
|
|
|
@@ -1103,7 +1200,6 @@ class ModelBuilder:
|
|
|
1103
1200
|
self.joint_type = []
|
|
1104
1201
|
self.joint_name = []
|
|
1105
1202
|
self.joint_armature = []
|
|
1106
|
-
self.joint_target = []
|
|
1107
1203
|
self.joint_target_ke = []
|
|
1108
1204
|
self.joint_target_kd = []
|
|
1109
1205
|
self.joint_axis_mode = []
|
|
@@ -1150,6 +1246,9 @@ class ModelBuilder:
|
|
|
1150
1246
|
# Maximum number of soft contacts that can be registered
|
|
1151
1247
|
self.soft_contact_max = 64 * 1024
|
|
1152
1248
|
|
|
1249
|
+
# maximum number of contact points to generate per mesh shape
|
|
1250
|
+
self.rigid_mesh_contact_max = 0 # 0 = unlimited
|
|
1251
|
+
|
|
1153
1252
|
# contacts to be generated within the given distance margin to be generated at
|
|
1154
1253
|
# every simulation substep (can be 0 if only one PBD solver iteration is used)
|
|
1155
1254
|
self.rigid_contact_margin = 0.1
|
|
@@ -1218,44 +1317,63 @@ class ModelBuilder:
|
|
|
1218
1317
|
def add_articulation(self):
|
|
1219
1318
|
self.articulation_start.append(self.joint_count)
|
|
1220
1319
|
|
|
1221
|
-
def add_builder(self,
|
|
1222
|
-
"""Copies
|
|
1320
|
+
def add_builder(self, builder, xform=None, update_num_env_count=True, separate_collision_group=True):
|
|
1321
|
+
"""Copies the data from `builder`, another `ModelBuilder` to this `ModelBuilder`.
|
|
1223
1322
|
|
|
1224
1323
|
Args:
|
|
1225
|
-
|
|
1324
|
+
builder (ModelBuilder): a model builder to add model data from.
|
|
1226
1325
|
xform (:ref:`transform <transform>`): offset transform applied to root bodies.
|
|
1227
1326
|
update_num_env_count (bool): if True, the number of environments is incremented by 1.
|
|
1228
|
-
separate_collision_group (bool): if True, the shapes from the
|
|
1327
|
+
separate_collision_group (bool): if True, the shapes from the articulations in `builder` will all be put into a single new collision group, otherwise, only the shapes in collision group > -1 will be moved to a new group.
|
|
1229
1328
|
"""
|
|
1230
1329
|
|
|
1330
|
+
start_particle_idx = self.particle_count
|
|
1331
|
+
if builder.particle_count:
|
|
1332
|
+
self.particle_max_velocity = builder.particle_max_velocity
|
|
1333
|
+
if xform is not None:
|
|
1334
|
+
pos_offset = wp.transform_get_translation(xform)
|
|
1335
|
+
else:
|
|
1336
|
+
pos_offset = np.zeros(3)
|
|
1337
|
+
self.particle_q.extend((np.array(builder.particle_q) + pos_offset).tolist())
|
|
1338
|
+
# other particle attributes are added below
|
|
1339
|
+
|
|
1340
|
+
if builder.spring_count:
|
|
1341
|
+
self.spring_indices.extend((np.array(builder.spring_indices, dtype=np.int32) + start_particle_idx).tolist())
|
|
1342
|
+
if builder.edge_count:
|
|
1343
|
+
self.edge_indices.extend((np.array(builder.edge_indices, dtype=np.int32) + start_particle_idx).tolist())
|
|
1344
|
+
if builder.tri_count:
|
|
1345
|
+
self.tri_indices.extend((np.array(builder.tri_indices, dtype=np.int32) + start_particle_idx).tolist())
|
|
1346
|
+
if builder.tet_count:
|
|
1347
|
+
self.tet_indices.extend((np.array(builder.tet_indices, dtype=np.int32) + start_particle_idx).tolist())
|
|
1348
|
+
|
|
1231
1349
|
start_body_idx = self.body_count
|
|
1232
1350
|
start_shape_idx = self.shape_count
|
|
1233
|
-
for s, b in enumerate(
|
|
1351
|
+
for s, b in enumerate(builder.shape_body):
|
|
1234
1352
|
if b > -1:
|
|
1235
1353
|
new_b = b + start_body_idx
|
|
1236
1354
|
self.shape_body.append(new_b)
|
|
1237
|
-
self.shape_transform.append(
|
|
1355
|
+
self.shape_transform.append(builder.shape_transform[s])
|
|
1238
1356
|
else:
|
|
1239
1357
|
self.shape_body.append(-1)
|
|
1240
1358
|
# apply offset transform to root bodies
|
|
1241
1359
|
if xform is not None:
|
|
1242
|
-
self.shape_transform.append(xform *
|
|
1360
|
+
self.shape_transform.append(xform * builder.shape_transform[s])
|
|
1243
1361
|
|
|
1244
|
-
for b, shapes in
|
|
1362
|
+
for b, shapes in builder.body_shapes.items():
|
|
1245
1363
|
self.body_shapes[b + start_body_idx] = [s + start_shape_idx for s in shapes]
|
|
1246
1364
|
|
|
1247
|
-
if
|
|
1248
|
-
joint_X_p = copy.deepcopy(
|
|
1249
|
-
joint_q = copy.deepcopy(
|
|
1365
|
+
if builder.joint_count:
|
|
1366
|
+
joint_X_p = copy.deepcopy(builder.joint_X_p)
|
|
1367
|
+
joint_q = copy.deepcopy(builder.joint_q)
|
|
1250
1368
|
if xform is not None:
|
|
1251
1369
|
for i in range(len(joint_X_p)):
|
|
1252
|
-
if
|
|
1253
|
-
qi =
|
|
1370
|
+
if builder.joint_type[i] == wp.sim.JOINT_FREE:
|
|
1371
|
+
qi = builder.joint_q_start[i]
|
|
1254
1372
|
xform_prev = wp.transform(joint_q[qi : qi + 3], joint_q[qi + 3 : qi + 7])
|
|
1255
1373
|
tf = xform * xform_prev
|
|
1256
1374
|
joint_q[qi : qi + 3] = tf.p
|
|
1257
1375
|
joint_q[qi + 3 : qi + 7] = tf.q
|
|
1258
|
-
elif
|
|
1376
|
+
elif builder.joint_parent[i] == -1:
|
|
1259
1377
|
joint_X_p[i] = xform * joint_X_p[i]
|
|
1260
1378
|
self.joint_X_p.extend(joint_X_p)
|
|
1261
1379
|
self.joint_q.extend(joint_q)
|
|
@@ -1263,35 +1381,33 @@ class ModelBuilder:
|
|
|
1263
1381
|
self.add_articulation()
|
|
1264
1382
|
|
|
1265
1383
|
# offset the indices
|
|
1266
|
-
self.joint_parent.extend([p + self.joint_count if p != -1 else -1 for p in
|
|
1267
|
-
self.joint_child.extend([c + self.joint_count for c in
|
|
1384
|
+
self.joint_parent.extend([p + self.joint_count if p != -1 else -1 for p in builder.joint_parent])
|
|
1385
|
+
self.joint_child.extend([c + self.joint_count for c in builder.joint_child])
|
|
1268
1386
|
|
|
1269
|
-
self.joint_q_start.extend([c + self.joint_coord_count for c in
|
|
1270
|
-
self.joint_qd_start.extend([c + self.joint_dof_count for c in
|
|
1387
|
+
self.joint_q_start.extend([c + self.joint_coord_count for c in builder.joint_q_start])
|
|
1388
|
+
self.joint_qd_start.extend([c + self.joint_dof_count for c in builder.joint_qd_start])
|
|
1271
1389
|
|
|
1272
|
-
self.joint_axis_start.extend([a + self.joint_axis_total_count for a in
|
|
1390
|
+
self.joint_axis_start.extend([a + self.joint_axis_total_count for a in builder.joint_axis_start])
|
|
1273
1391
|
|
|
1274
|
-
joint_children = set(
|
|
1275
|
-
for i in range(
|
|
1392
|
+
joint_children = set(builder.joint_child)
|
|
1393
|
+
for i in range(builder.body_count):
|
|
1276
1394
|
if xform is not None and i not in joint_children:
|
|
1277
1395
|
# rigid body is not attached to a joint, so apply input transform directly
|
|
1278
|
-
self.body_q.append(xform *
|
|
1396
|
+
self.body_q.append(xform * builder.body_q[i])
|
|
1279
1397
|
else:
|
|
1280
|
-
self.body_q.append(
|
|
1398
|
+
self.body_q.append(builder.body_q[i])
|
|
1281
1399
|
|
|
1282
1400
|
# apply collision group
|
|
1283
1401
|
if separate_collision_group:
|
|
1284
|
-
self.shape_collision_group.extend(
|
|
1285
|
-
[self.last_collision_group + 1 for _ in articulation.shape_collision_group]
|
|
1286
|
-
)
|
|
1402
|
+
self.shape_collision_group.extend([self.last_collision_group + 1 for _ in builder.shape_collision_group])
|
|
1287
1403
|
else:
|
|
1288
1404
|
self.shape_collision_group.extend(
|
|
1289
|
-
[(g + self.last_collision_group if g > -1 else -1) for g in
|
|
1405
|
+
[(g + self.last_collision_group if g > -1 else -1) for g in builder.shape_collision_group]
|
|
1290
1406
|
)
|
|
1291
1407
|
shape_count = self.shape_count
|
|
1292
|
-
for i, j in
|
|
1408
|
+
for i, j in builder.shape_collision_filter_pairs:
|
|
1293
1409
|
self.shape_collision_filter_pairs.add((i + shape_count, j + shape_count))
|
|
1294
|
-
for group, shapes in
|
|
1410
|
+
for group, shapes in builder.shape_collision_group_map.items():
|
|
1295
1411
|
if separate_collision_group:
|
|
1296
1412
|
group = self.last_collision_group + 1
|
|
1297
1413
|
else:
|
|
@@ -1303,10 +1419,10 @@ class ModelBuilder:
|
|
|
1303
1419
|
# update last collision group counter
|
|
1304
1420
|
if separate_collision_group:
|
|
1305
1421
|
self.last_collision_group += 1
|
|
1306
|
-
elif
|
|
1307
|
-
self.last_collision_group +=
|
|
1422
|
+
elif builder.last_collision_group > -1:
|
|
1423
|
+
self.last_collision_group += builder.last_collision_group
|
|
1308
1424
|
|
|
1309
|
-
|
|
1425
|
+
more_builder_attrs = [
|
|
1310
1426
|
"body_inertia",
|
|
1311
1427
|
"body_mass",
|
|
1312
1428
|
"body_inv_inertia",
|
|
@@ -1328,11 +1444,11 @@ class ModelBuilder:
|
|
|
1328
1444
|
"joint_limit_upper",
|
|
1329
1445
|
"joint_limit_ke",
|
|
1330
1446
|
"joint_limit_kd",
|
|
1331
|
-
"joint_target",
|
|
1332
1447
|
"joint_target_ke",
|
|
1333
1448
|
"joint_target_kd",
|
|
1334
1449
|
"joint_linear_compliance",
|
|
1335
1450
|
"joint_angular_compliance",
|
|
1451
|
+
"shape_visible",
|
|
1336
1452
|
"shape_geo_type",
|
|
1337
1453
|
"shape_geo_scale",
|
|
1338
1454
|
"shape_geo_src",
|
|
@@ -1341,21 +1457,39 @@ class ModelBuilder:
|
|
|
1341
1457
|
"shape_material_ke",
|
|
1342
1458
|
"shape_material_kd",
|
|
1343
1459
|
"shape_material_kf",
|
|
1460
|
+
"shape_material_ka",
|
|
1344
1461
|
"shape_material_mu",
|
|
1345
1462
|
"shape_material_restitution",
|
|
1346
1463
|
"shape_collision_radius",
|
|
1347
1464
|
"shape_ground_collision",
|
|
1465
|
+
"particle_qd",
|
|
1466
|
+
"particle_mass",
|
|
1467
|
+
"particle_radius",
|
|
1468
|
+
"particle_flags",
|
|
1469
|
+
"edge_rest_angle",
|
|
1470
|
+
"edge_bending_properties",
|
|
1471
|
+
"spring_rest_length",
|
|
1472
|
+
"spring_stiffness",
|
|
1473
|
+
"spring_damping",
|
|
1474
|
+
"spring_control",
|
|
1475
|
+
"tri_poses",
|
|
1476
|
+
"tri_activations",
|
|
1477
|
+
"tri_materials",
|
|
1478
|
+
"tet_poses",
|
|
1479
|
+
"tet_activations",
|
|
1480
|
+
"tet_materials",
|
|
1348
1481
|
]
|
|
1349
1482
|
|
|
1350
|
-
for attr in
|
|
1351
|
-
getattr(self, attr).extend(getattr(
|
|
1483
|
+
for attr in more_builder_attrs:
|
|
1484
|
+
getattr(self, attr).extend(getattr(builder, attr))
|
|
1352
1485
|
|
|
1353
|
-
self.joint_dof_count +=
|
|
1354
|
-
self.joint_coord_count +=
|
|
1355
|
-
self.joint_axis_total_count +=
|
|
1486
|
+
self.joint_dof_count += builder.joint_dof_count
|
|
1487
|
+
self.joint_coord_count += builder.joint_coord_count
|
|
1488
|
+
self.joint_axis_total_count += builder.joint_axis_total_count
|
|
1356
1489
|
|
|
1357
|
-
self.up_vector =
|
|
1358
|
-
self.gravity =
|
|
1490
|
+
self.up_vector = builder.up_vector
|
|
1491
|
+
self.gravity = builder.gravity
|
|
1492
|
+
self._ground_params = builder._ground_params
|
|
1359
1493
|
|
|
1360
1494
|
if update_num_env_count:
|
|
1361
1495
|
self.num_envs += 1
|
|
@@ -1425,6 +1559,7 @@ class ModelBuilder:
|
|
|
1425
1559
|
child_xform: wp.transform = wp.transform(),
|
|
1426
1560
|
linear_compliance: float = 0.0,
|
|
1427
1561
|
angular_compliance: float = 0.0,
|
|
1562
|
+
armature: float = 1e-2,
|
|
1428
1563
|
collision_filter_parent: bool = True,
|
|
1429
1564
|
enabled: bool = True,
|
|
1430
1565
|
) -> int:
|
|
@@ -1432,18 +1567,19 @@ class ModelBuilder:
|
|
|
1432
1567
|
Generic method to add any type of joint to this ModelBuilder.
|
|
1433
1568
|
|
|
1434
1569
|
Args:
|
|
1435
|
-
joint_type: The type of joint to add (see `Joint types`_)
|
|
1436
|
-
parent: The index of the parent body (-1 is the world)
|
|
1437
|
-
child: The index of the child body
|
|
1438
|
-
linear_axes: The linear axes (see :class:`JointAxis`) of the joint
|
|
1439
|
-
angular_axes: The angular axes (see :class:`JointAxis`) of the joint
|
|
1440
|
-
name: The name of the joint
|
|
1570
|
+
joint_type (constant): The type of joint to add (see `Joint types`_)
|
|
1571
|
+
parent (int): The index of the parent body (-1 is the world)
|
|
1572
|
+
child (int): The index of the child body
|
|
1573
|
+
linear_axes (list(:class:`JointAxis`)): The linear axes (see :class:`JointAxis`) of the joint
|
|
1574
|
+
angular_axes (list(:class:`JointAxis`)): The angular axes (see :class:`JointAxis`) of the joint
|
|
1575
|
+
name (str): The name of the joint (optional)
|
|
1441
1576
|
parent_xform (:ref:`transform <transform>`): The transform of the joint in the parent body's local frame
|
|
1442
1577
|
child_xform (:ref:`transform <transform>`): The transform of the joint in the child body's local frame
|
|
1443
|
-
linear_compliance: The linear compliance of the joint
|
|
1444
|
-
angular_compliance: The angular compliance of the joint
|
|
1445
|
-
|
|
1446
|
-
|
|
1578
|
+
linear_compliance (float): The linear compliance of the joint
|
|
1579
|
+
angular_compliance (float): The angular compliance of the joint
|
|
1580
|
+
armature (float): Artificial inertia added around the joint axis (only considered by :class:`FeatherstoneIntegrator`)
|
|
1581
|
+
collision_filter_parent (bool): Whether to filter collisions between shapes of the parent and child bodies
|
|
1582
|
+
enabled (bool): Whether the joint is enabled (not considered by :class:`FeatherstoneIntegrator`)
|
|
1447
1583
|
|
|
1448
1584
|
Returns:
|
|
1449
1585
|
The index of the added joint
|
|
@@ -1469,10 +1605,10 @@ class ModelBuilder:
|
|
|
1469
1605
|
self.joint_angular_compliance.append(angular_compliance)
|
|
1470
1606
|
self.joint_enabled.append(enabled)
|
|
1471
1607
|
|
|
1472
|
-
def add_axis_dim(dim):
|
|
1608
|
+
def add_axis_dim(dim: JointAxis):
|
|
1473
1609
|
self.joint_axis.append(dim.axis)
|
|
1474
1610
|
self.joint_axis_mode.append(dim.mode)
|
|
1475
|
-
self.
|
|
1611
|
+
self.joint_act.append(dim.action)
|
|
1476
1612
|
self.joint_target_ke.append(dim.target_ke)
|
|
1477
1613
|
self.joint_target_kd.append(dim.target_kd)
|
|
1478
1614
|
self.joint_limit_ke.append(dim.limit_ke)
|
|
@@ -1485,8 +1621,6 @@ class ModelBuilder:
|
|
|
1485
1621
|
self.joint_limit_upper.append(dim.limit_upper)
|
|
1486
1622
|
else:
|
|
1487
1623
|
self.joint_limit_upper.append(1e6)
|
|
1488
|
-
# self.joint_limit_lower.append(dim.limit_lower)
|
|
1489
|
-
# self.joint_limit_upper.append(dim.limit_upper)
|
|
1490
1624
|
|
|
1491
1625
|
for dim in linear_axes:
|
|
1492
1626
|
add_axis_dim(dim)
|
|
@@ -1523,7 +1657,7 @@ class ModelBuilder:
|
|
|
1523
1657
|
|
|
1524
1658
|
for i in range(dof_count):
|
|
1525
1659
|
self.joint_qd.append(0.0)
|
|
1526
|
-
self.
|
|
1660
|
+
self.joint_armature.append(armature)
|
|
1527
1661
|
|
|
1528
1662
|
if joint_type == JOINT_FREE or joint_type == JOINT_DISTANCE or joint_type == JOINT_BALL:
|
|
1529
1663
|
# ensure that a valid quaternion is used for the angular dofs
|
|
@@ -1546,13 +1680,13 @@ class ModelBuilder:
|
|
|
1546
1680
|
self,
|
|
1547
1681
|
parent: int,
|
|
1548
1682
|
child: int,
|
|
1549
|
-
parent_xform: wp.transform,
|
|
1550
|
-
child_xform: wp.transform,
|
|
1551
|
-
axis: Vec3,
|
|
1552
|
-
target: float =
|
|
1683
|
+
parent_xform: wp.transform = wp.transform(),
|
|
1684
|
+
child_xform: wp.transform = wp.transform(),
|
|
1685
|
+
axis: Vec3 = (1.0, 0.0, 0.0),
|
|
1686
|
+
target: float = None,
|
|
1553
1687
|
target_ke: float = 0.0,
|
|
1554
1688
|
target_kd: float = 0.0,
|
|
1555
|
-
mode: int =
|
|
1689
|
+
mode: int = JOINT_MODE_FORCE,
|
|
1556
1690
|
limit_lower: float = -2 * math.pi,
|
|
1557
1691
|
limit_upper: float = 2 * math.pi,
|
|
1558
1692
|
limit_ke: float = default_joint_limit_ke,
|
|
@@ -1571,7 +1705,7 @@ class ModelBuilder:
|
|
|
1571
1705
|
parent_xform (:ref:`transform <transform>`): The transform of the joint in the parent body's local frame
|
|
1572
1706
|
child_xform (:ref:`transform <transform>`): The transform of the joint in the child body's local frame
|
|
1573
1707
|
axis (3D vector or JointAxis): The axis of rotation in the parent body's local frame, can be a JointAxis object whose settings will be used instead of the other arguments
|
|
1574
|
-
target: The target angle (in radians) of the joint
|
|
1708
|
+
target: The target angle (in radians) or target velocity of the joint (if None, the joint is considered to be in force control mode)
|
|
1575
1709
|
target_ke: The stiffness of the joint target
|
|
1576
1710
|
target_kd: The damping of the joint target
|
|
1577
1711
|
limit_lower: The lower limit of the joint
|
|
@@ -1588,11 +1722,18 @@ class ModelBuilder:
|
|
|
1588
1722
|
The index of the added joint
|
|
1589
1723
|
|
|
1590
1724
|
"""
|
|
1725
|
+
action = 0.0
|
|
1726
|
+
if target is None and mode == JOINT_MODE_TARGET_POSITION:
|
|
1727
|
+
action = 0.5 * (limit_lower + limit_upper)
|
|
1728
|
+
elif target is not None:
|
|
1729
|
+
action = target
|
|
1730
|
+
if mode == JOINT_MODE_FORCE:
|
|
1731
|
+
mode = JOINT_MODE_TARGET_POSITION
|
|
1591
1732
|
ax = JointAxis(
|
|
1592
1733
|
axis=axis,
|
|
1593
1734
|
limit_lower=limit_lower,
|
|
1594
1735
|
limit_upper=limit_upper,
|
|
1595
|
-
|
|
1736
|
+
action=action,
|
|
1596
1737
|
target_ke=target_ke,
|
|
1597
1738
|
target_kd=target_kd,
|
|
1598
1739
|
mode=mode,
|
|
@@ -1617,13 +1758,13 @@ class ModelBuilder:
|
|
|
1617
1758
|
self,
|
|
1618
1759
|
parent: int,
|
|
1619
1760
|
child: int,
|
|
1620
|
-
parent_xform: wp.transform,
|
|
1621
|
-
child_xform: wp.transform,
|
|
1622
|
-
axis: Vec3,
|
|
1623
|
-
target: float =
|
|
1761
|
+
parent_xform: wp.transform = wp.transform(),
|
|
1762
|
+
child_xform: wp.transform = wp.transform(),
|
|
1763
|
+
axis: Vec3 = (1.0, 0.0, 0.0),
|
|
1764
|
+
target: float = None,
|
|
1624
1765
|
target_ke: float = 0.0,
|
|
1625
1766
|
target_kd: float = 0.0,
|
|
1626
|
-
mode: int =
|
|
1767
|
+
mode: int = JOINT_MODE_FORCE,
|
|
1627
1768
|
limit_lower: float = -1e4,
|
|
1628
1769
|
limit_upper: float = 1e4,
|
|
1629
1770
|
limit_ke: float = default_joint_limit_ke,
|
|
@@ -1642,7 +1783,7 @@ class ModelBuilder:
|
|
|
1642
1783
|
parent_xform (:ref:`transform <transform>`): The transform of the joint in the parent body's local frame
|
|
1643
1784
|
child_xform (:ref:`transform <transform>`): The transform of the joint in the child body's local frame
|
|
1644
1785
|
axis (3D vector or JointAxis): The axis of rotation in the parent body's local frame, can be a JointAxis object whose settings will be used instead of the other arguments
|
|
1645
|
-
target: The target position of the joint
|
|
1786
|
+
target: The target position or velocity of the joint (if None, the joint is considered to be in force control mode)
|
|
1646
1787
|
target_ke: The stiffness of the joint target
|
|
1647
1788
|
target_kd: The damping of the joint target
|
|
1648
1789
|
limit_lower: The lower limit of the joint
|
|
@@ -1659,11 +1800,18 @@ class ModelBuilder:
|
|
|
1659
1800
|
The index of the added joint
|
|
1660
1801
|
|
|
1661
1802
|
"""
|
|
1803
|
+
action = 0.0
|
|
1804
|
+
if target is None and mode == JOINT_MODE_TARGET_POSITION:
|
|
1805
|
+
action = 0.5 * (limit_lower + limit_upper)
|
|
1806
|
+
elif target is not None:
|
|
1807
|
+
action = target
|
|
1808
|
+
if mode == JOINT_MODE_FORCE:
|
|
1809
|
+
mode = JOINT_MODE_TARGET_POSITION
|
|
1662
1810
|
ax = JointAxis(
|
|
1663
1811
|
axis=axis,
|
|
1664
1812
|
limit_lower=limit_lower,
|
|
1665
1813
|
limit_upper=limit_upper,
|
|
1666
|
-
|
|
1814
|
+
action=action,
|
|
1667
1815
|
target_ke=target_ke,
|
|
1668
1816
|
target_kd=target_kd,
|
|
1669
1817
|
mode=mode,
|
|
@@ -1692,6 +1840,7 @@ class ModelBuilder:
|
|
|
1692
1840
|
child_xform: wp.transform = wp.transform(),
|
|
1693
1841
|
linear_compliance: float = 0.0,
|
|
1694
1842
|
angular_compliance: float = 0.0,
|
|
1843
|
+
armature: float = 1e-2,
|
|
1695
1844
|
name: str = None,
|
|
1696
1845
|
collision_filter_parent: bool = True,
|
|
1697
1846
|
enabled: bool = True,
|
|
@@ -1705,6 +1854,7 @@ class ModelBuilder:
|
|
|
1705
1854
|
child_xform (:ref:`transform <transform>`): The transform of the joint in the child body's local frame
|
|
1706
1855
|
linear_compliance: The linear compliance of the joint
|
|
1707
1856
|
angular_compliance: The angular compliance of the joint
|
|
1857
|
+
armature (float): Artificial inertia added around the joint axis (only considered by FeatherstoneIntegrator)
|
|
1708
1858
|
name: The name of the joint
|
|
1709
1859
|
collision_filter_parent: Whether to filter collisions between shapes of the parent and child bodies
|
|
1710
1860
|
enabled: Whether the joint is enabled
|
|
@@ -1721,6 +1871,7 @@ class ModelBuilder:
|
|
|
1721
1871
|
child_xform=child_xform,
|
|
1722
1872
|
linear_compliance=linear_compliance,
|
|
1723
1873
|
angular_compliance=angular_compliance,
|
|
1874
|
+
armature=armature,
|
|
1724
1875
|
name=name,
|
|
1725
1876
|
collision_filter_parent=collision_filter_parent,
|
|
1726
1877
|
enabled=enabled,
|
|
@@ -1774,6 +1925,7 @@ class ModelBuilder:
|
|
|
1774
1925
|
child: int,
|
|
1775
1926
|
parent_xform: wp.transform = wp.transform(),
|
|
1776
1927
|
child_xform: wp.transform = wp.transform(),
|
|
1928
|
+
armature: float = 0.0,
|
|
1777
1929
|
parent: int = -1,
|
|
1778
1930
|
name: str = None,
|
|
1779
1931
|
collision_filter_parent: bool = True,
|
|
@@ -1786,6 +1938,7 @@ class ModelBuilder:
|
|
|
1786
1938
|
child: The index of the child body
|
|
1787
1939
|
parent_xform (:ref:`transform <transform>`): The transform of the joint in the parent body's local frame
|
|
1788
1940
|
child_xform (:ref:`transform <transform>`): The transform of the joint in the child body's local frame
|
|
1941
|
+
armature (float): Artificial inertia added around the joint axis (only considered by FeatherstoneIntegrator)
|
|
1789
1942
|
parent: The index of the parent body (-1 by default to use the world frame, e.g. to make the child body and its children a floating-base mechanism)
|
|
1790
1943
|
name: The name of the joint
|
|
1791
1944
|
collision_filter_parent: Whether to filter collisions between shapes of the parent and child bodies
|
|
@@ -1801,6 +1954,7 @@ class ModelBuilder:
|
|
|
1801
1954
|
child,
|
|
1802
1955
|
parent_xform=parent_xform,
|
|
1803
1956
|
child_xform=child_xform,
|
|
1957
|
+
armature=armature,
|
|
1804
1958
|
name=name,
|
|
1805
1959
|
collision_filter_parent=collision_filter_parent,
|
|
1806
1960
|
enabled=enabled,
|
|
@@ -1834,7 +1988,7 @@ class ModelBuilder:
|
|
|
1834
1988
|
|
|
1835
1989
|
Returns:
|
|
1836
1990
|
The index of the added joint
|
|
1837
|
-
|
|
1991
|
+
|
|
1838
1992
|
.. note:: Distance joints are currently only supported in the :class:`XPBDIntegrator` at the moment.
|
|
1839
1993
|
|
|
1840
1994
|
"""
|
|
@@ -1996,6 +2150,43 @@ class ModelBuilder:
|
|
|
1996
2150
|
enabled=enabled,
|
|
1997
2151
|
)
|
|
1998
2152
|
|
|
2153
|
+
def plot_articulation(self, plot_shapes=True):
|
|
2154
|
+
"""Plots the model's articulation."""
|
|
2155
|
+
|
|
2156
|
+
def joint_type_str(type):
|
|
2157
|
+
if type == JOINT_FREE:
|
|
2158
|
+
return "free"
|
|
2159
|
+
elif type == JOINT_BALL:
|
|
2160
|
+
return "ball"
|
|
2161
|
+
elif type == JOINT_PRISMATIC:
|
|
2162
|
+
return "prismatic"
|
|
2163
|
+
elif type == JOINT_REVOLUTE:
|
|
2164
|
+
return "revolute"
|
|
2165
|
+
elif type == JOINT_D6:
|
|
2166
|
+
return "D6"
|
|
2167
|
+
elif type == JOINT_UNIVERSAL:
|
|
2168
|
+
return "universal"
|
|
2169
|
+
elif type == JOINT_COMPOUND:
|
|
2170
|
+
return "compound"
|
|
2171
|
+
elif type == JOINT_FIXED:
|
|
2172
|
+
return "fixed"
|
|
2173
|
+
elif type == JOINT_DISTANCE:
|
|
2174
|
+
return "distance"
|
|
2175
|
+
return "unknown"
|
|
2176
|
+
|
|
2177
|
+
vertices = ["world"] + self.body_name
|
|
2178
|
+
if plot_shapes:
|
|
2179
|
+
vertices += [f"shape_{i}" for i in range(self.shape_count)]
|
|
2180
|
+
edges = []
|
|
2181
|
+
edge_labels = []
|
|
2182
|
+
for i in range(self.joint_count):
|
|
2183
|
+
edges.append((self.joint_child[i] + 1, self.joint_parent[i] + 1))
|
|
2184
|
+
edge_labels.append(f"{self.joint_name[i]}\n({joint_type_str(self.joint_type[i])})")
|
|
2185
|
+
if plot_shapes:
|
|
2186
|
+
for i in range(self.shape_count):
|
|
2187
|
+
edges.append((len(self.body_name) + i + 1, self.shape_body[i] + 1))
|
|
2188
|
+
wp.plot_graph(vertices, edges, edge_labels=edge_labels)
|
|
2189
|
+
|
|
1999
2190
|
def collapse_fixed_joints(self, verbose=wp.config.verbose):
|
|
2000
2191
|
"""Removes fixed joints from the model and merges the bodies they connect. This is useful for simplifying the model for faster and more stable simulation."""
|
|
2001
2192
|
|
|
@@ -2037,10 +2228,10 @@ class ModelBuilder:
|
|
|
2037
2228
|
|
|
2038
2229
|
data = {
|
|
2039
2230
|
"type": self.joint_type[i],
|
|
2040
|
-
# 'armature': self.joint_armature[i],
|
|
2041
2231
|
"q": self.joint_q[q_start : q_start + q_dim],
|
|
2042
2232
|
"qd": self.joint_qd[qd_start : qd_start + qd_dim],
|
|
2043
2233
|
"act": self.joint_act[qd_start : qd_start + qd_dim],
|
|
2234
|
+
"armature": self.joint_armature[qd_start : qd_start + qd_dim],
|
|
2044
2235
|
"q_start": q_start,
|
|
2045
2236
|
"qd_start": qd_start,
|
|
2046
2237
|
"linear_compliance": self.joint_linear_compliance[i],
|
|
@@ -2062,7 +2253,6 @@ class ModelBuilder:
|
|
|
2062
2253
|
{
|
|
2063
2254
|
"axis": self.joint_axis[j],
|
|
2064
2255
|
"axis_mode": self.joint_axis_mode[j],
|
|
2065
|
-
"target": self.joint_target[j],
|
|
2066
2256
|
"target_ke": self.joint_target_ke[j],
|
|
2067
2257
|
"target_kd": self.joint_target_kd[j],
|
|
2068
2258
|
"limit_ke": self.joint_limit_ke[j],
|
|
@@ -2176,10 +2366,10 @@ class ModelBuilder:
|
|
|
2176
2366
|
# recompute inverse mass and inertia
|
|
2177
2367
|
if m > 0.0:
|
|
2178
2368
|
self.body_inv_mass.append(1.0 / m)
|
|
2179
|
-
self.body_inv_inertia.append(
|
|
2369
|
+
self.body_inv_inertia.append(wp.inverse(inertia))
|
|
2180
2370
|
else:
|
|
2181
2371
|
self.body_inv_mass.append(0.0)
|
|
2182
|
-
self.body_inv_inertia.append(
|
|
2372
|
+
self.body_inv_inertia.append(wp.mat33(0.0))
|
|
2183
2373
|
else:
|
|
2184
2374
|
self.body_inv_mass.append(body["inv_mass"])
|
|
2185
2375
|
self.body_inv_inertia.append(body["inv_inertia"])
|
|
@@ -2200,11 +2390,11 @@ class ModelBuilder:
|
|
|
2200
2390
|
self.joint_enabled.clear()
|
|
2201
2391
|
self.joint_linear_compliance.clear()
|
|
2202
2392
|
self.joint_angular_compliance.clear()
|
|
2393
|
+
self.joint_armature.clear()
|
|
2203
2394
|
self.joint_X_p.clear()
|
|
2204
2395
|
self.joint_X_c.clear()
|
|
2205
2396
|
self.joint_axis.clear()
|
|
2206
2397
|
self.joint_axis_mode.clear()
|
|
2207
|
-
self.joint_target.clear()
|
|
2208
2398
|
self.joint_target_ke.clear()
|
|
2209
2399
|
self.joint_target_kd.clear()
|
|
2210
2400
|
self.joint_limit_lower.clear()
|
|
@@ -2224,6 +2414,7 @@ class ModelBuilder:
|
|
|
2224
2414
|
self.joint_q.extend(joint["q"])
|
|
2225
2415
|
self.joint_qd.extend(joint["qd"])
|
|
2226
2416
|
self.joint_act.extend(joint["act"])
|
|
2417
|
+
self.joint_armature.extend(joint["armature"])
|
|
2227
2418
|
self.joint_enabled.append(joint["enabled"])
|
|
2228
2419
|
self.joint_linear_compliance.append(joint["linear_compliance"])
|
|
2229
2420
|
self.joint_angular_compliance.append(joint["angular_compliance"])
|
|
@@ -2234,7 +2425,6 @@ class ModelBuilder:
|
|
|
2234
2425
|
for axis in joint["axes"]:
|
|
2235
2426
|
self.joint_axis.append(axis["axis"])
|
|
2236
2427
|
self.joint_axis_mode.append(axis["axis_mode"])
|
|
2237
|
-
self.joint_target.append(axis["target"])
|
|
2238
2428
|
self.joint_target_ke.append(axis["target_ke"])
|
|
2239
2429
|
self.joint_target_kd.append(axis["target_kd"])
|
|
2240
2430
|
self.joint_limit_lower.append(axis["limit_lower"])
|
|
@@ -2267,7 +2457,7 @@ class ModelBuilder:
|
|
|
2267
2457
|
|
|
2268
2458
|
self.muscle_start.append(len(self.muscle_bodies))
|
|
2269
2459
|
self.muscle_params.append((f0, lm, lt, lmax, pen))
|
|
2270
|
-
self.
|
|
2460
|
+
self.muscle_activations.append(0.0)
|
|
2271
2461
|
|
|
2272
2462
|
for i in range(n):
|
|
2273
2463
|
self.muscle_bodies.append(bodies[i])
|
|
@@ -2285,13 +2475,15 @@ class ModelBuilder:
|
|
|
2285
2475
|
width: float = 10.0,
|
|
2286
2476
|
length: float = 10.0,
|
|
2287
2477
|
body: int = -1,
|
|
2288
|
-
ke: float =
|
|
2289
|
-
kd: float =
|
|
2290
|
-
kf: float =
|
|
2291
|
-
|
|
2292
|
-
|
|
2293
|
-
|
|
2478
|
+
ke: float = None,
|
|
2479
|
+
kd: float = None,
|
|
2480
|
+
kf: float = None,
|
|
2481
|
+
ka: float = None,
|
|
2482
|
+
mu: float = None,
|
|
2483
|
+
restitution: float = None,
|
|
2484
|
+
thickness: float = None,
|
|
2294
2485
|
has_ground_collision: bool = False,
|
|
2486
|
+
is_visible: bool = True,
|
|
2295
2487
|
collision_group: int = -1,
|
|
2296
2488
|
):
|
|
2297
2489
|
"""
|
|
@@ -2306,13 +2498,15 @@ class ModelBuilder:
|
|
|
2306
2498
|
width: The extent along x of the plane (infinite if 0)
|
|
2307
2499
|
length: The extent along z of the plane (infinite if 0)
|
|
2308
2500
|
body: The body index to attach the shape to (-1 by default to keep the plane static)
|
|
2309
|
-
ke: The contact elastic stiffness
|
|
2310
|
-
kd: The contact damping stiffness
|
|
2311
|
-
kf: The contact friction stiffness
|
|
2312
|
-
|
|
2313
|
-
|
|
2314
|
-
|
|
2501
|
+
ke: The contact elastic stiffness (None to use the default value :attr:`default_shape_ke`)
|
|
2502
|
+
kd: The contact damping stiffness (None to use the default value :attr:`default_shape_kd`)
|
|
2503
|
+
kf: The contact friction stiffness (None to use the default value :attr:`default_shape_kf`)
|
|
2504
|
+
ka: The contact adhesion distance (None to use the default value :attr:`default_shape_ka`)
|
|
2505
|
+
mu: The coefficient of friction (None to use the default value :attr:`default_shape_mu`)
|
|
2506
|
+
restitution: The coefficient of restitution (None to use the default value :attr:`default_shape_restitution`)
|
|
2507
|
+
thickness: The thickness of the plane (0 by default) for collision handling (None to use the default value :attr:`default_shape_thickness`)
|
|
2315
2508
|
has_ground_collision: If True, the mesh will collide with the ground plane if `Model.ground` is True
|
|
2509
|
+
is_visible: Whether the plane is visible
|
|
2316
2510
|
collision_group: The collision group of the shape
|
|
2317
2511
|
|
|
2318
2512
|
Returns:
|
|
@@ -2330,7 +2524,7 @@ class ModelBuilder:
|
|
|
2330
2524
|
else:
|
|
2331
2525
|
c = np.cross(normal, (0.0, 1.0, 0.0))
|
|
2332
2526
|
angle = np.arcsin(np.linalg.norm(c))
|
|
2333
|
-
axis = c / np.linalg.norm(c)
|
|
2527
|
+
axis = np.abs(c) / np.linalg.norm(c)
|
|
2334
2528
|
rot = wp.quat_from_axis_angle(axis, angle)
|
|
2335
2529
|
scale = wp.vec3(width, length, 0.0)
|
|
2336
2530
|
|
|
@@ -2345,10 +2539,12 @@ class ModelBuilder:
|
|
|
2345
2539
|
ke,
|
|
2346
2540
|
kd,
|
|
2347
2541
|
kf,
|
|
2542
|
+
ka,
|
|
2348
2543
|
mu,
|
|
2349
2544
|
restitution,
|
|
2350
2545
|
thickness,
|
|
2351
2546
|
has_ground_collision=has_ground_collision,
|
|
2547
|
+
is_visible=is_visible,
|
|
2352
2548
|
collision_group=collision_group,
|
|
2353
2549
|
)
|
|
2354
2550
|
|
|
@@ -2358,16 +2554,18 @@ class ModelBuilder:
|
|
|
2358
2554
|
pos: Vec3 = (0.0, 0.0, 0.0),
|
|
2359
2555
|
rot: Quat = (0.0, 0.0, 0.0, 1.0),
|
|
2360
2556
|
radius: float = 1.0,
|
|
2361
|
-
density: float =
|
|
2362
|
-
ke: float =
|
|
2363
|
-
kd: float =
|
|
2364
|
-
kf: float =
|
|
2365
|
-
|
|
2366
|
-
|
|
2557
|
+
density: float = None,
|
|
2558
|
+
ke: float = None,
|
|
2559
|
+
kd: float = None,
|
|
2560
|
+
kf: float = None,
|
|
2561
|
+
ka: float = None,
|
|
2562
|
+
mu: float = None,
|
|
2563
|
+
restitution: float = None,
|
|
2367
2564
|
is_solid: bool = True,
|
|
2368
|
-
thickness: float =
|
|
2565
|
+
thickness: float = None,
|
|
2369
2566
|
has_ground_collision: bool = True,
|
|
2370
2567
|
collision_group: int = -1,
|
|
2568
|
+
is_visible: bool = True,
|
|
2371
2569
|
):
|
|
2372
2570
|
"""Adds a sphere collision shape to a body.
|
|
2373
2571
|
|
|
@@ -2376,22 +2574,25 @@ class ModelBuilder:
|
|
|
2376
2574
|
pos: The location of the shape with respect to the parent frame
|
|
2377
2575
|
rot: The rotation of the shape with respect to the parent frame
|
|
2378
2576
|
radius: The radius of the sphere
|
|
2379
|
-
density: The density of the shape
|
|
2380
|
-
ke: The contact elastic stiffness
|
|
2381
|
-
kd: The contact damping stiffness
|
|
2382
|
-
kf: The contact friction stiffness
|
|
2383
|
-
|
|
2384
|
-
|
|
2577
|
+
density: The density of the shape (None to use the default value :attr:`default_shape_density`)
|
|
2578
|
+
ke: The contact elastic stiffness (None to use the default value :attr:`default_shape_ke`)
|
|
2579
|
+
kd: The contact damping stiffness (None to use the default value :attr:`default_shape_kd`)
|
|
2580
|
+
kf: The contact friction stiffness (None to use the default value :attr:`default_shape_kf`)
|
|
2581
|
+
ka: The contact adhesion distance (None to use the default value :attr:`default_shape_ka`)
|
|
2582
|
+
mu: The coefficient of friction (None to use the default value :attr:`default_shape_mu`)
|
|
2583
|
+
restitution: The coefficient of restitution (None to use the default value :attr:`default_shape_restitution`)
|
|
2385
2584
|
is_solid: Whether the sphere is solid or hollow
|
|
2386
|
-
thickness: Thickness to use for computing inertia of a hollow sphere, and for collision handling
|
|
2585
|
+
thickness: Thickness to use for computing inertia of a hollow sphere, and for collision handling (None to use the default value :attr:`default_shape_thickness`)
|
|
2387
2586
|
has_ground_collision: If True, the mesh will collide with the ground plane if `Model.ground` is True
|
|
2388
2587
|
collision_group: The collision group of the shape
|
|
2588
|
+
is_visible: Whether the sphere is visible
|
|
2389
2589
|
|
|
2390
2590
|
Returns:
|
|
2391
2591
|
The index of the added shape
|
|
2392
2592
|
|
|
2393
2593
|
"""
|
|
2394
2594
|
|
|
2595
|
+
thickness = self.default_shape_thickness if thickness is None else thickness
|
|
2395
2596
|
return self._add_shape(
|
|
2396
2597
|
body,
|
|
2397
2598
|
wp.vec3(pos),
|
|
@@ -2403,12 +2604,14 @@ class ModelBuilder:
|
|
|
2403
2604
|
ke,
|
|
2404
2605
|
kd,
|
|
2405
2606
|
kf,
|
|
2607
|
+
ka,
|
|
2406
2608
|
mu,
|
|
2407
2609
|
restitution,
|
|
2408
2610
|
thickness + radius,
|
|
2409
2611
|
is_solid,
|
|
2410
2612
|
has_ground_collision=has_ground_collision,
|
|
2411
2613
|
collision_group=collision_group,
|
|
2614
|
+
is_visible=is_visible,
|
|
2412
2615
|
)
|
|
2413
2616
|
|
|
2414
2617
|
def add_shape_box(
|
|
@@ -2419,16 +2622,18 @@ class ModelBuilder:
|
|
|
2419
2622
|
hx: float = 0.5,
|
|
2420
2623
|
hy: float = 0.5,
|
|
2421
2624
|
hz: float = 0.5,
|
|
2422
|
-
density: float =
|
|
2423
|
-
ke: float =
|
|
2424
|
-
kd: float =
|
|
2425
|
-
kf: float =
|
|
2426
|
-
|
|
2427
|
-
|
|
2625
|
+
density: float = None,
|
|
2626
|
+
ke: float = None,
|
|
2627
|
+
kd: float = None,
|
|
2628
|
+
kf: float = None,
|
|
2629
|
+
ka: float = None,
|
|
2630
|
+
mu: float = None,
|
|
2631
|
+
restitution: float = None,
|
|
2428
2632
|
is_solid: bool = True,
|
|
2429
|
-
thickness: float =
|
|
2633
|
+
thickness: float = None,
|
|
2430
2634
|
has_ground_collision: bool = True,
|
|
2431
2635
|
collision_group: int = -1,
|
|
2636
|
+
is_visible: bool = True,
|
|
2432
2637
|
):
|
|
2433
2638
|
"""Adds a box collision shape to a body.
|
|
2434
2639
|
|
|
@@ -2439,16 +2644,18 @@ class ModelBuilder:
|
|
|
2439
2644
|
hx: The half-extent along the x-axis
|
|
2440
2645
|
hy: The half-extent along the y-axis
|
|
2441
2646
|
hz: The half-extent along the z-axis
|
|
2442
|
-
density: The density of the shape
|
|
2443
|
-
ke: The contact elastic stiffness
|
|
2444
|
-
kd: The contact damping stiffness
|
|
2445
|
-
kf: The contact friction stiffness
|
|
2446
|
-
|
|
2447
|
-
|
|
2647
|
+
density: The density of the shape (None to use the default value :attr:`default_shape_density`)
|
|
2648
|
+
ke: The contact elastic stiffness (None to use the default value :attr:`default_shape_ke`)
|
|
2649
|
+
kd: The contact damping stiffness (None to use the default value :attr:`default_shape_kd`)
|
|
2650
|
+
kf: The contact friction stiffness (None to use the default value :attr:`default_shape_kf`)
|
|
2651
|
+
ka: The contact adhesion distance (None to use the default value :attr:`default_shape_ka`)
|
|
2652
|
+
mu: The coefficient of friction (None to use the default value :attr:`default_shape_mu`)
|
|
2653
|
+
restitution: The coefficient of restitution (None to use the default value :attr:`default_shape_restitution`)
|
|
2448
2654
|
is_solid: Whether the box is solid or hollow
|
|
2449
|
-
thickness: Thickness to use for computing inertia of a hollow box, and for collision handling
|
|
2655
|
+
thickness: Thickness to use for computing inertia of a hollow box, and for collision handling (None to use the default value :attr:`default_shape_thickness`)
|
|
2450
2656
|
has_ground_collision: If True, the mesh will collide with the ground plane if `Model.ground` is True
|
|
2451
2657
|
collision_group: The collision group of the shape
|
|
2658
|
+
is_visible: Whether the box is visible
|
|
2452
2659
|
|
|
2453
2660
|
Returns:
|
|
2454
2661
|
The index of the added shape
|
|
@@ -2466,12 +2673,14 @@ class ModelBuilder:
|
|
|
2466
2673
|
ke,
|
|
2467
2674
|
kd,
|
|
2468
2675
|
kf,
|
|
2676
|
+
ka,
|
|
2469
2677
|
mu,
|
|
2470
2678
|
restitution,
|
|
2471
2679
|
thickness,
|
|
2472
2680
|
is_solid,
|
|
2473
2681
|
has_ground_collision=has_ground_collision,
|
|
2474
2682
|
collision_group=collision_group,
|
|
2683
|
+
is_visible=is_visible,
|
|
2475
2684
|
)
|
|
2476
2685
|
|
|
2477
2686
|
def add_shape_capsule(
|
|
@@ -2482,16 +2691,18 @@ class ModelBuilder:
|
|
|
2482
2691
|
radius: float = 1.0,
|
|
2483
2692
|
half_height: float = 0.5,
|
|
2484
2693
|
up_axis: int = 1,
|
|
2485
|
-
density: float =
|
|
2486
|
-
ke: float =
|
|
2487
|
-
kd: float =
|
|
2488
|
-
kf: float =
|
|
2489
|
-
|
|
2490
|
-
|
|
2694
|
+
density: float = None,
|
|
2695
|
+
ke: float = None,
|
|
2696
|
+
kd: float = None,
|
|
2697
|
+
kf: float = None,
|
|
2698
|
+
ka: float = None,
|
|
2699
|
+
mu: float = None,
|
|
2700
|
+
restitution: float = None,
|
|
2491
2701
|
is_solid: bool = True,
|
|
2492
|
-
thickness: float =
|
|
2702
|
+
thickness: float = None,
|
|
2493
2703
|
has_ground_collision: bool = True,
|
|
2494
2704
|
collision_group: int = -1,
|
|
2705
|
+
is_visible: bool = True,
|
|
2495
2706
|
):
|
|
2496
2707
|
"""Adds a capsule collision shape to a body.
|
|
2497
2708
|
|
|
@@ -2502,16 +2713,18 @@ class ModelBuilder:
|
|
|
2502
2713
|
radius: The radius of the capsule
|
|
2503
2714
|
half_height: The half length of the center cylinder along the up axis
|
|
2504
2715
|
up_axis: The axis along which the capsule is aligned (0=x, 1=y, 2=z)
|
|
2505
|
-
density: The density of the shape
|
|
2506
|
-
ke: The contact elastic stiffness
|
|
2507
|
-
kd: The contact damping stiffness
|
|
2508
|
-
kf: The contact friction stiffness
|
|
2509
|
-
|
|
2510
|
-
|
|
2716
|
+
density: The density of the shape (None to use the default value :attr:`default_shape_density`)
|
|
2717
|
+
ke: The contact elastic stiffness (None to use the default value :attr:`default_shape_ke`)
|
|
2718
|
+
kd: The contact damping stiffness (None to use the default value :attr:`default_shape_kd`)
|
|
2719
|
+
kf: The contact friction stiffness (None to use the default value :attr:`default_shape_kf`)
|
|
2720
|
+
ka: The contact adhesion distance (None to use the default value :attr:`default_shape_ka`)
|
|
2721
|
+
mu: The coefficient of friction (None to use the default value :attr:`default_shape_mu`)
|
|
2722
|
+
restitution: The coefficient of restitution (None to use the default value :attr:`default_shape_restitution`)
|
|
2511
2723
|
is_solid: Whether the capsule is solid or hollow
|
|
2512
|
-
thickness: Thickness to use for computing inertia of a hollow capsule, and for collision handling
|
|
2724
|
+
thickness: Thickness to use for computing inertia of a hollow capsule, and for collision handling (None to use the default value :attr:`default_shape_thickness`)
|
|
2513
2725
|
has_ground_collision: If True, the mesh will collide with the ground plane if `Model.ground` is True
|
|
2514
2726
|
collision_group: The collision group of the shape
|
|
2727
|
+
is_visible: Whether the capsule is visible
|
|
2515
2728
|
|
|
2516
2729
|
Returns:
|
|
2517
2730
|
The index of the added shape
|
|
@@ -2525,6 +2738,7 @@ class ModelBuilder:
|
|
|
2525
2738
|
elif up_axis == 2:
|
|
2526
2739
|
q = wp.mul(q, wp.quat(sqh, 0.0, 0.0, sqh))
|
|
2527
2740
|
|
|
2741
|
+
thickness = self.default_shape_thickness if thickness is None else thickness
|
|
2528
2742
|
return self._add_shape(
|
|
2529
2743
|
body,
|
|
2530
2744
|
wp.vec3(pos),
|
|
@@ -2536,12 +2750,14 @@ class ModelBuilder:
|
|
|
2536
2750
|
ke,
|
|
2537
2751
|
kd,
|
|
2538
2752
|
kf,
|
|
2753
|
+
ka,
|
|
2539
2754
|
mu,
|
|
2540
2755
|
restitution,
|
|
2541
2756
|
thickness + radius,
|
|
2542
2757
|
is_solid,
|
|
2543
2758
|
has_ground_collision=has_ground_collision,
|
|
2544
2759
|
collision_group=collision_group,
|
|
2760
|
+
is_visible=is_visible,
|
|
2545
2761
|
)
|
|
2546
2762
|
|
|
2547
2763
|
def add_shape_cylinder(
|
|
@@ -2552,16 +2768,18 @@ class ModelBuilder:
|
|
|
2552
2768
|
radius: float = 1.0,
|
|
2553
2769
|
half_height: float = 0.5,
|
|
2554
2770
|
up_axis: int = 1,
|
|
2555
|
-
density: float =
|
|
2556
|
-
ke: float =
|
|
2557
|
-
kd: float =
|
|
2558
|
-
kf: float =
|
|
2559
|
-
|
|
2560
|
-
|
|
2771
|
+
density: float = None,
|
|
2772
|
+
ke: float = None,
|
|
2773
|
+
kd: float = None,
|
|
2774
|
+
kf: float = None,
|
|
2775
|
+
ka: float = None,
|
|
2776
|
+
mu: float = None,
|
|
2777
|
+
restitution: float = None,
|
|
2561
2778
|
is_solid: bool = True,
|
|
2562
|
-
thickness: float =
|
|
2779
|
+
thickness: float = None,
|
|
2563
2780
|
has_ground_collision: bool = True,
|
|
2564
2781
|
collision_group: int = -1,
|
|
2782
|
+
is_visible: bool = True,
|
|
2565
2783
|
):
|
|
2566
2784
|
"""Adds a cylinder collision shape to a body.
|
|
2567
2785
|
|
|
@@ -2572,16 +2790,21 @@ class ModelBuilder:
|
|
|
2572
2790
|
radius: The radius of the cylinder
|
|
2573
2791
|
half_height: The half length of the cylinder along the up axis
|
|
2574
2792
|
up_axis: The axis along which the cylinder is aligned (0=x, 1=y, 2=z)
|
|
2575
|
-
density: The density of the shape
|
|
2576
|
-
ke: The contact elastic stiffness
|
|
2577
|
-
kd: The contact damping stiffness
|
|
2578
|
-
kf: The contact friction stiffness
|
|
2579
|
-
|
|
2580
|
-
|
|
2793
|
+
density: The density of the shape (None to use the default value :attr:`default_shape_density`)
|
|
2794
|
+
ke: The contact elastic stiffness (None to use the default value :attr:`default_shape_ke`)
|
|
2795
|
+
kd: The contact damping stiffness (None to use the default value :attr:`default_shape_kd`)
|
|
2796
|
+
kf: The contact friction stiffness (None to use the default value :attr:`default_shape_kf`)
|
|
2797
|
+
ka: The contact adhesion distance (None to use the default value :attr:`default_shape_ka`)
|
|
2798
|
+
mu: The coefficient of friction (None to use the default value :attr:`default_shape_mu`)
|
|
2799
|
+
restitution: The coefficient of restitution (None to use the default value :attr:`default_shape_restitution`)
|
|
2581
2800
|
is_solid: Whether the cylinder is solid or hollow
|
|
2582
|
-
thickness: Thickness to use for computing inertia of a hollow cylinder, and for collision handling
|
|
2801
|
+
thickness: Thickness to use for computing inertia of a hollow cylinder, and for collision handling (None to use the default value :attr:`default_shape_thickness`)
|
|
2583
2802
|
has_ground_collision: If True, the mesh will collide with the ground plane if `Model.ground` is True
|
|
2584
2803
|
collision_group: The collision group of the shape
|
|
2804
|
+
is_visible: Whether the cylinder is visible
|
|
2805
|
+
|
|
2806
|
+
Note:
|
|
2807
|
+
Cylinders are currently not supported in rigid body collision handling.
|
|
2585
2808
|
|
|
2586
2809
|
Returns:
|
|
2587
2810
|
The index of the added shape
|
|
@@ -2606,12 +2829,14 @@ class ModelBuilder:
|
|
|
2606
2829
|
ke,
|
|
2607
2830
|
kd,
|
|
2608
2831
|
kf,
|
|
2832
|
+
ka,
|
|
2609
2833
|
mu,
|
|
2610
2834
|
restitution,
|
|
2611
2835
|
thickness,
|
|
2612
2836
|
is_solid,
|
|
2613
2837
|
has_ground_collision=has_ground_collision,
|
|
2614
2838
|
collision_group=collision_group,
|
|
2839
|
+
is_visible=is_visible,
|
|
2615
2840
|
)
|
|
2616
2841
|
|
|
2617
2842
|
def add_shape_cone(
|
|
@@ -2622,16 +2847,18 @@ class ModelBuilder:
|
|
|
2622
2847
|
radius: float = 1.0,
|
|
2623
2848
|
half_height: float = 0.5,
|
|
2624
2849
|
up_axis: int = 1,
|
|
2625
|
-
density: float =
|
|
2626
|
-
ke: float =
|
|
2627
|
-
kd: float =
|
|
2628
|
-
kf: float =
|
|
2629
|
-
|
|
2630
|
-
|
|
2850
|
+
density: float = None,
|
|
2851
|
+
ke: float = None,
|
|
2852
|
+
kd: float = None,
|
|
2853
|
+
kf: float = None,
|
|
2854
|
+
ka: float = None,
|
|
2855
|
+
mu: float = None,
|
|
2856
|
+
restitution: float = None,
|
|
2631
2857
|
is_solid: bool = True,
|
|
2632
|
-
thickness: float =
|
|
2858
|
+
thickness: float = None,
|
|
2633
2859
|
has_ground_collision: bool = True,
|
|
2634
2860
|
collision_group: int = -1,
|
|
2861
|
+
is_visible: bool = True,
|
|
2635
2862
|
):
|
|
2636
2863
|
"""Adds a cone collision shape to a body.
|
|
2637
2864
|
|
|
@@ -2642,16 +2869,21 @@ class ModelBuilder:
|
|
|
2642
2869
|
radius: The radius of the cone
|
|
2643
2870
|
half_height: The half length of the cone along the up axis
|
|
2644
2871
|
up_axis: The axis along which the cone is aligned (0=x, 1=y, 2=z)
|
|
2645
|
-
density: The density of the shape
|
|
2646
|
-
ke: The contact elastic stiffness
|
|
2647
|
-
kd: The contact damping stiffness
|
|
2648
|
-
kf: The contact friction stiffness
|
|
2649
|
-
|
|
2650
|
-
|
|
2872
|
+
density: The density of the shape (None to use the default value :attr:`default_shape_density`)
|
|
2873
|
+
ke: The contact elastic stiffness (None to use the default value :attr:`default_shape_ke`)
|
|
2874
|
+
kd: The contact damping stiffness (None to use the default value :attr:`default_shape_kd`)
|
|
2875
|
+
kf: The contact friction stiffness (None to use the default value :attr:`default_shape_kf`)
|
|
2876
|
+
ka: The contact adhesion distance (None to use the default value :attr:`default_shape_ka`)
|
|
2877
|
+
mu: The coefficient of friction (None to use the default value :attr:`default_shape_mu`)
|
|
2878
|
+
restitution: The coefficient of restitution (None to use the default value :attr:`default_shape_restitution`)
|
|
2651
2879
|
is_solid: Whether the cone is solid or hollow
|
|
2652
|
-
thickness: Thickness to use for computing inertia of a hollow cone, and for collision handling
|
|
2880
|
+
thickness: Thickness to use for computing inertia of a hollow cone, and for collision handling (None to use the default value :attr:`default_shape_thickness`)
|
|
2653
2881
|
has_ground_collision: If True, the mesh will collide with the ground plane if `Model.ground` is True
|
|
2654
2882
|
collision_group: The collision group of the shape
|
|
2883
|
+
is_visible: Whether the cone is visible
|
|
2884
|
+
|
|
2885
|
+
Note:
|
|
2886
|
+
Cones are currently not supported in rigid body collision handling.
|
|
2655
2887
|
|
|
2656
2888
|
Returns:
|
|
2657
2889
|
The index of the added shape
|
|
@@ -2676,12 +2908,14 @@ class ModelBuilder:
|
|
|
2676
2908
|
ke,
|
|
2677
2909
|
kd,
|
|
2678
2910
|
kf,
|
|
2911
|
+
ka,
|
|
2679
2912
|
mu,
|
|
2680
2913
|
restitution,
|
|
2681
2914
|
thickness,
|
|
2682
2915
|
is_solid,
|
|
2683
2916
|
has_ground_collision=has_ground_collision,
|
|
2684
2917
|
collision_group=collision_group,
|
|
2918
|
+
is_visible=is_visible,
|
|
2685
2919
|
)
|
|
2686
2920
|
|
|
2687
2921
|
def add_shape_mesh(
|
|
@@ -2691,16 +2925,18 @@ class ModelBuilder:
|
|
|
2691
2925
|
rot: Quat = wp.quat(0.0, 0.0, 0.0, 1.0),
|
|
2692
2926
|
mesh: Mesh = None,
|
|
2693
2927
|
scale: Vec3 = wp.vec3(1.0, 1.0, 1.0),
|
|
2694
|
-
density: float =
|
|
2695
|
-
ke: float =
|
|
2696
|
-
kd: float =
|
|
2697
|
-
kf: float =
|
|
2698
|
-
|
|
2699
|
-
|
|
2928
|
+
density: float = None,
|
|
2929
|
+
ke: float = None,
|
|
2930
|
+
kd: float = None,
|
|
2931
|
+
kf: float = None,
|
|
2932
|
+
ka: float = None,
|
|
2933
|
+
mu: float = None,
|
|
2934
|
+
restitution: float = None,
|
|
2700
2935
|
is_solid: bool = True,
|
|
2701
|
-
thickness: float =
|
|
2936
|
+
thickness: float = None,
|
|
2702
2937
|
has_ground_collision: bool = True,
|
|
2703
2938
|
collision_group: int = -1,
|
|
2939
|
+
is_visible: bool = True,
|
|
2704
2940
|
):
|
|
2705
2941
|
"""Adds a triangle mesh collision shape to a body.
|
|
2706
2942
|
|
|
@@ -2710,16 +2946,18 @@ class ModelBuilder:
|
|
|
2710
2946
|
rot: The rotation of the shape with respect to the parent frame
|
|
2711
2947
|
mesh: The mesh object
|
|
2712
2948
|
scale: Scale to use for the collider
|
|
2713
|
-
density: The density of the shape
|
|
2714
|
-
ke: The contact elastic stiffness
|
|
2715
|
-
kd: The contact damping stiffness
|
|
2716
|
-
kf: The contact friction stiffness
|
|
2717
|
-
|
|
2718
|
-
|
|
2949
|
+
density: The density of the shape (None to use the default value :attr:`default_shape_density`)
|
|
2950
|
+
ke: The contact elastic stiffness (None to use the default value :attr:`default_shape_ke`)
|
|
2951
|
+
kd: The contact damping stiffness (None to use the default value :attr:`default_shape_kd`)
|
|
2952
|
+
kf: The contact friction stiffness (None to use the default value :attr:`default_shape_kf`)
|
|
2953
|
+
ka: The contact adhesion distance (None to use the default value :attr:`default_shape_ka`)
|
|
2954
|
+
mu: The coefficient of friction (None to use the default value :attr:`default_shape_mu`)
|
|
2955
|
+
restitution: The coefficient of restitution (None to use the default value :attr:`default_shape_restitution`)
|
|
2719
2956
|
is_solid: If True, the mesh is solid, otherwise it is a hollow surface with the given wall thickness
|
|
2720
|
-
thickness: Thickness to use for computing inertia of a hollow mesh, and for collision handling
|
|
2957
|
+
thickness: Thickness to use for computing inertia of a hollow mesh, and for collision handling (None to use the default value :attr:`default_shape_thickness`)
|
|
2721
2958
|
has_ground_collision: If True, the mesh will collide with the ground plane if `Model.ground` is True
|
|
2722
2959
|
collision_group: The collision group of the shape
|
|
2960
|
+
is_visible: Whether the mesh is visible
|
|
2723
2961
|
|
|
2724
2962
|
Returns:
|
|
2725
2963
|
The index of the added shape
|
|
@@ -2737,12 +2975,14 @@ class ModelBuilder:
|
|
|
2737
2975
|
ke,
|
|
2738
2976
|
kd,
|
|
2739
2977
|
kf,
|
|
2978
|
+
ka,
|
|
2740
2979
|
mu,
|
|
2741
2980
|
restitution,
|
|
2742
2981
|
thickness,
|
|
2743
2982
|
is_solid,
|
|
2744
2983
|
has_ground_collision=has_ground_collision,
|
|
2745
2984
|
collision_group=collision_group,
|
|
2985
|
+
is_visible=is_visible,
|
|
2746
2986
|
)
|
|
2747
2987
|
|
|
2748
2988
|
def add_shape_sdf(
|
|
@@ -2752,15 +2992,18 @@ class ModelBuilder:
|
|
|
2752
2992
|
rot: Quat = (0.0, 0.0, 0.0, 1.0),
|
|
2753
2993
|
sdf: SDF = None,
|
|
2754
2994
|
scale: Vec3 = (1.0, 1.0, 1.0),
|
|
2755
|
-
density: float =
|
|
2756
|
-
ke: float =
|
|
2757
|
-
kd: float =
|
|
2758
|
-
kf: float =
|
|
2759
|
-
|
|
2760
|
-
|
|
2995
|
+
density: float = None,
|
|
2996
|
+
ke: float = None,
|
|
2997
|
+
kd: float = None,
|
|
2998
|
+
kf: float = None,
|
|
2999
|
+
ka: float = None,
|
|
3000
|
+
mu: float = None,
|
|
3001
|
+
restitution: float = None,
|
|
2761
3002
|
is_solid: bool = True,
|
|
2762
|
-
thickness: float =
|
|
3003
|
+
thickness: float = None,
|
|
3004
|
+
has_ground_collision: bool = True,
|
|
2763
3005
|
collision_group: int = -1,
|
|
3006
|
+
is_visible: bool = True,
|
|
2764
3007
|
):
|
|
2765
3008
|
"""Adds SDF collision shape to a body.
|
|
2766
3009
|
|
|
@@ -2770,16 +3013,18 @@ class ModelBuilder:
|
|
|
2770
3013
|
rot: The rotation of the shape with respect to the parent frame
|
|
2771
3014
|
sdf: The sdf object
|
|
2772
3015
|
scale: Scale to use for the collider
|
|
2773
|
-
density: The density of the shape
|
|
2774
|
-
ke: The contact elastic stiffness
|
|
2775
|
-
kd: The contact damping stiffness
|
|
2776
|
-
kf: The contact friction stiffness
|
|
2777
|
-
|
|
2778
|
-
|
|
2779
|
-
|
|
2780
|
-
|
|
2781
|
-
|
|
3016
|
+
density: The density of the shape (None to use the default value :attr:`default_shape_density`)
|
|
3017
|
+
ke: The contact elastic stiffness (None to use the default value :attr:`default_shape_ke`)
|
|
3018
|
+
kd: The contact damping stiffness (None to use the default value :attr:`default_shape_kd`)
|
|
3019
|
+
kf: The contact friction stiffness (None to use the default value :attr:`default_shape_kf`)
|
|
3020
|
+
ka: The contact adhesion distance (None to use the default value :attr:`default_shape_ka`)
|
|
3021
|
+
mu: The coefficient of friction (None to use the default value :attr:`default_shape_mu`)
|
|
3022
|
+
restitution: The coefficient of restitution (None to use the default value :attr:`default_shape_restitution`)
|
|
3023
|
+
is_solid: If True, the SDF is solid, otherwise it is a hollow surface with the given wall thickness
|
|
3024
|
+
thickness: Thickness to use for collision handling (None to use the default value :attr:`default_shape_thickness`)
|
|
3025
|
+
has_ground_collision: If True, the shape will collide with the ground plane if `Model.ground` is True
|
|
2782
3026
|
collision_group: The collision group of the shape
|
|
3027
|
+
is_visible: Whether the shape is visible
|
|
2783
3028
|
|
|
2784
3029
|
Returns:
|
|
2785
3030
|
The index of the added shape
|
|
@@ -2796,11 +3041,14 @@ class ModelBuilder:
|
|
|
2796
3041
|
ke,
|
|
2797
3042
|
kd,
|
|
2798
3043
|
kf,
|
|
3044
|
+
ka,
|
|
2799
3045
|
mu,
|
|
2800
3046
|
restitution,
|
|
2801
3047
|
thickness,
|
|
2802
3048
|
is_solid,
|
|
3049
|
+
has_ground_collision=has_ground_collision,
|
|
2803
3050
|
collision_group=collision_group,
|
|
3051
|
+
is_visible=is_visible,
|
|
2804
3052
|
)
|
|
2805
3053
|
|
|
2806
3054
|
def _shape_radius(self, type, scale, src):
|
|
@@ -2832,18 +3080,20 @@ class ModelBuilder:
|
|
|
2832
3080
|
rot,
|
|
2833
3081
|
type,
|
|
2834
3082
|
scale,
|
|
2835
|
-
src,
|
|
2836
|
-
density,
|
|
2837
|
-
ke,
|
|
2838
|
-
kd,
|
|
2839
|
-
kf,
|
|
2840
|
-
|
|
2841
|
-
|
|
2842
|
-
|
|
3083
|
+
src=None,
|
|
3084
|
+
density=None,
|
|
3085
|
+
ke=None,
|
|
3086
|
+
kd=None,
|
|
3087
|
+
kf=None,
|
|
3088
|
+
ka=None,
|
|
3089
|
+
mu=None,
|
|
3090
|
+
restitution=None,
|
|
3091
|
+
thickness=None,
|
|
2843
3092
|
is_solid=True,
|
|
2844
3093
|
collision_group=-1,
|
|
2845
3094
|
collision_filter_parent=True,
|
|
2846
3095
|
has_ground_collision=True,
|
|
3096
|
+
is_visible=True,
|
|
2847
3097
|
):
|
|
2848
3098
|
self.shape_body.append(body)
|
|
2849
3099
|
shape = self.shape_count
|
|
@@ -2854,7 +3104,16 @@ class ModelBuilder:
|
|
|
2854
3104
|
self.body_shapes[body].append(shape)
|
|
2855
3105
|
else:
|
|
2856
3106
|
self.body_shapes[body] = [shape]
|
|
3107
|
+
ke = ke if ke is not None else self.default_shape_ke
|
|
3108
|
+
kd = kd if kd is not None else self.default_shape_kd
|
|
3109
|
+
kf = kf if kf is not None else self.default_shape_kf
|
|
3110
|
+
ka = ka if ka is not None else self.default_shape_ka
|
|
3111
|
+
mu = mu if mu is not None else self.default_shape_mu
|
|
3112
|
+
restitution = restitution if restitution is not None else self.default_shape_restitution
|
|
3113
|
+
thickness = thickness if thickness is not None else self.default_shape_thickness
|
|
3114
|
+
density = density if density is not None else self.default_shape_density
|
|
2857
3115
|
self.shape_transform.append(wp.transform(pos, rot))
|
|
3116
|
+
self.shape_visible.append(is_visible)
|
|
2858
3117
|
self.shape_geo_type.append(type)
|
|
2859
3118
|
self.shape_geo_scale.append((scale[0], scale[1], scale[2]))
|
|
2860
3119
|
self.shape_geo_src.append(src)
|
|
@@ -2863,6 +3122,7 @@ class ModelBuilder:
|
|
|
2863
3122
|
self.shape_material_ke.append(ke)
|
|
2864
3123
|
self.shape_material_kd.append(kd)
|
|
2865
3124
|
self.shape_material_kf.append(kf)
|
|
3125
|
+
self.shape_material_ka.append(ka)
|
|
2866
3126
|
self.shape_material_mu.append(mu)
|
|
2867
3127
|
self.shape_material_restitution.append(restitution)
|
|
2868
3128
|
self.shape_collision_group.append(collision_group)
|
|
@@ -3831,13 +4091,9 @@ class ModelBuilder:
|
|
|
3831
4091
|
self._create_ground_plane()
|
|
3832
4092
|
|
|
3833
4093
|
# construct particle inv masses
|
|
3834
|
-
|
|
3835
|
-
|
|
3836
|
-
|
|
3837
|
-
if m > 0.0:
|
|
3838
|
-
particle_inv_mass.append(1.0 / m)
|
|
3839
|
-
else:
|
|
3840
|
-
particle_inv_mass.append(0.0)
|
|
4094
|
+
ms = np.array(self.particle_mass, dtype=np.float32)
|
|
4095
|
+
# static particles (with zero mass) have zero inverse mass
|
|
4096
|
+
particle_inv_mass = np.divide(1.0, ms, out=np.zeros_like(ms), where=ms != 0.0)
|
|
3841
4097
|
|
|
3842
4098
|
with wp.ScopedDevice(device):
|
|
3843
4099
|
# -------------------------------------
|
|
@@ -3846,6 +4102,8 @@ class ModelBuilder:
|
|
|
3846
4102
|
m = Model(device)
|
|
3847
4103
|
m.requires_grad = requires_grad
|
|
3848
4104
|
|
|
4105
|
+
m.ground_plane_params = self._ground_params["plane"]
|
|
4106
|
+
|
|
3849
4107
|
m.num_envs = self.num_envs
|
|
3850
4108
|
|
|
3851
4109
|
# ---------------------
|
|
@@ -3856,7 +4114,7 @@ class ModelBuilder:
|
|
|
3856
4114
|
m.particle_qd = wp.array(self.particle_qd, dtype=wp.vec3, requires_grad=requires_grad)
|
|
3857
4115
|
m.particle_mass = wp.array(self.particle_mass, dtype=wp.float32, requires_grad=requires_grad)
|
|
3858
4116
|
m.particle_inv_mass = wp.array(particle_inv_mass, dtype=wp.float32, requires_grad=requires_grad)
|
|
3859
|
-
m.
|
|
4117
|
+
m.particle_radius = wp.array(self.particle_radius, dtype=wp.float32, requires_grad=requires_grad)
|
|
3860
4118
|
m.particle_flags = wp.array([flag_to_int(f) for f in self.particle_flags], dtype=wp.uint32)
|
|
3861
4119
|
m.particle_max_radius = np.max(self.particle_radius) if len(self.particle_radius) > 0 else 0.0
|
|
3862
4120
|
m.particle_max_velocity = self.particle_max_velocity
|
|
@@ -3869,6 +4127,7 @@ class ModelBuilder:
|
|
|
3869
4127
|
|
|
3870
4128
|
m.shape_transform = wp.array(self.shape_transform, dtype=wp.transform, requires_grad=requires_grad)
|
|
3871
4129
|
m.shape_body = wp.array(self.shape_body, dtype=wp.int32)
|
|
4130
|
+
m.shape_visible = wp.array(self.shape_visible, dtype=wp.bool)
|
|
3872
4131
|
m.body_shapes = self.body_shapes
|
|
3873
4132
|
|
|
3874
4133
|
# build list of ids for geometry sources (meshes, sdfs)
|
|
@@ -3890,10 +4149,14 @@ class ModelBuilder:
|
|
|
3890
4149
|
m.shape_geo.is_solid = wp.array(self.shape_geo_is_solid, dtype=wp.uint8)
|
|
3891
4150
|
m.shape_geo.thickness = wp.array(self.shape_geo_thickness, dtype=wp.float32, requires_grad=requires_grad)
|
|
3892
4151
|
m.shape_geo_src = self.shape_geo_src # used for rendering
|
|
4152
|
+
# store refs to geometry
|
|
4153
|
+
m.geo_meshes = self.geo_meshes
|
|
4154
|
+
m.geo_sdfs = self.geo_sdfs
|
|
3893
4155
|
|
|
3894
4156
|
m.shape_materials.ke = wp.array(self.shape_material_ke, dtype=wp.float32, requires_grad=requires_grad)
|
|
3895
4157
|
m.shape_materials.kd = wp.array(self.shape_material_kd, dtype=wp.float32, requires_grad=requires_grad)
|
|
3896
4158
|
m.shape_materials.kf = wp.array(self.shape_material_kf, dtype=wp.float32, requires_grad=requires_grad)
|
|
4159
|
+
m.shape_materials.ka = wp.array(self.shape_material_ka, dtype=wp.float32, requires_grad=requires_grad)
|
|
3897
4160
|
m.shape_materials.mu = wp.array(self.shape_material_mu, dtype=wp.float32, requires_grad=requires_grad)
|
|
3898
4161
|
m.shape_materials.restitution = wp.array(
|
|
3899
4162
|
self.shape_material_restitution, dtype=wp.float32, requires_grad=requires_grad
|
|
@@ -3915,9 +4178,6 @@ class ModelBuilder:
|
|
|
3915
4178
|
m.spring_stiffness = wp.array(self.spring_stiffness, dtype=wp.float32, requires_grad=requires_grad)
|
|
3916
4179
|
m.spring_damping = wp.array(self.spring_damping, dtype=wp.float32, requires_grad=requires_grad)
|
|
3917
4180
|
m.spring_control = wp.array(self.spring_control, dtype=wp.float32, requires_grad=requires_grad)
|
|
3918
|
-
m.spring_constraint_lambdas = wp.array(
|
|
3919
|
-
shape=len(self.spring_rest_length), dtype=wp.float32, requires_grad=requires_grad
|
|
3920
|
-
)
|
|
3921
4181
|
|
|
3922
4182
|
# ---------------------
|
|
3923
4183
|
# triangles
|
|
@@ -3935,9 +4195,6 @@ class ModelBuilder:
|
|
|
3935
4195
|
m.edge_bending_properties = wp.array(
|
|
3936
4196
|
self.edge_bending_properties, dtype=wp.float32, requires_grad=requires_grad
|
|
3937
4197
|
)
|
|
3938
|
-
m.edge_constraint_lambdas = wp.array(
|
|
3939
|
-
shape=len(self.edge_rest_angle), dtype=wp.float32, requires_grad=requires_grad
|
|
3940
|
-
)
|
|
3941
4198
|
|
|
3942
4199
|
# ---------------------
|
|
3943
4200
|
# tetrahedra
|
|
@@ -3958,7 +4215,7 @@ class ModelBuilder:
|
|
|
3958
4215
|
m.muscle_params = wp.array(self.muscle_params, dtype=wp.float32, requires_grad=requires_grad)
|
|
3959
4216
|
m.muscle_bodies = wp.array(self.muscle_bodies, dtype=wp.int32)
|
|
3960
4217
|
m.muscle_points = wp.array(self.muscle_points, dtype=wp.vec3, requires_grad=requires_grad)
|
|
3961
|
-
m.
|
|
4218
|
+
m.muscle_activations = wp.array(self.muscle_activations, dtype=wp.float32, requires_grad=requires_grad)
|
|
3962
4219
|
|
|
3963
4220
|
# --------------------------------------
|
|
3964
4221
|
# rigid bodies
|
|
@@ -3973,8 +4230,6 @@ class ModelBuilder:
|
|
|
3973
4230
|
m.body_name = self.body_name
|
|
3974
4231
|
|
|
3975
4232
|
# joints
|
|
3976
|
-
m.joint_count = self.joint_count
|
|
3977
|
-
m.joint_axis_count = self.joint_axis_count
|
|
3978
4233
|
m.joint_type = wp.array(self.joint_type, dtype=wp.int32)
|
|
3979
4234
|
m.joint_parent = wp.array(self.joint_parent, dtype=wp.int32)
|
|
3980
4235
|
m.joint_child = wp.array(self.joint_child, dtype=wp.int32)
|
|
@@ -3988,12 +4243,10 @@ class ModelBuilder:
|
|
|
3988
4243
|
m.joint_name = self.joint_name
|
|
3989
4244
|
|
|
3990
4245
|
# dynamics properties
|
|
3991
|
-
# TODO unused joint_armature
|
|
3992
4246
|
m.joint_armature = wp.array(self.joint_armature, dtype=wp.float32, requires_grad=requires_grad)
|
|
3993
|
-
m.joint_target = wp.array(self.joint_target, dtype=wp.float32, requires_grad=requires_grad)
|
|
3994
4247
|
m.joint_target_ke = wp.array(self.joint_target_ke, dtype=wp.float32, requires_grad=requires_grad)
|
|
3995
4248
|
m.joint_target_kd = wp.array(self.joint_target_kd, dtype=wp.float32, requires_grad=requires_grad)
|
|
3996
|
-
m.joint_axis_mode = wp.array(self.joint_axis_mode, dtype=wp.
|
|
4249
|
+
m.joint_axis_mode = wp.array(self.joint_axis_mode, dtype=wp.int32)
|
|
3997
4250
|
m.joint_act = wp.array(self.joint_act, dtype=wp.float32, requires_grad=requires_grad)
|
|
3998
4251
|
|
|
3999
4252
|
m.joint_limit_lower = wp.array(self.joint_limit_lower, dtype=wp.float32, requires_grad=requires_grad)
|
|
@@ -4021,6 +4274,10 @@ class ModelBuilder:
|
|
|
4021
4274
|
m.articulation_start = wp.array(articulation_start, dtype=wp.int32)
|
|
4022
4275
|
|
|
4023
4276
|
# counts
|
|
4277
|
+
m.joint_count = self.joint_count
|
|
4278
|
+
m.joint_axis_count = self.joint_axis_count
|
|
4279
|
+
m.joint_dof_count = self.joint_dof_count
|
|
4280
|
+
m.joint_coord_count = self.joint_coord_count
|
|
4024
4281
|
m.particle_count = len(self.particle_q)
|
|
4025
4282
|
m.body_count = len(self.body_q)
|
|
4026
4283
|
m.shape_count = len(self.shape_geo_type)
|
|
@@ -4036,23 +4293,20 @@ class ModelBuilder:
|
|
|
4036
4293
|
m.allocate_soft_contacts(self.soft_contact_max, requires_grad=requires_grad)
|
|
4037
4294
|
m.find_shape_contact_pairs()
|
|
4038
4295
|
if self.num_rigid_contacts_per_env is None:
|
|
4039
|
-
contact_count = m.count_contact_points()
|
|
4296
|
+
contact_count, limited_contact_count = m.count_contact_points()
|
|
4040
4297
|
else:
|
|
4041
|
-
contact_count = self.num_rigid_contacts_per_env * self.num_envs
|
|
4042
|
-
if
|
|
4043
|
-
|
|
4044
|
-
|
|
4298
|
+
contact_count = limited_contact_count = self.num_rigid_contacts_per_env * self.num_envs
|
|
4299
|
+
if contact_count:
|
|
4300
|
+
if wp.config.verbose:
|
|
4301
|
+
print(f"Allocating {contact_count} rigid contacts.")
|
|
4302
|
+
m.allocate_rigid_contacts(
|
|
4303
|
+
count=contact_count, limited_contact_count=limited_contact_count, requires_grad=requires_grad
|
|
4304
|
+
)
|
|
4305
|
+
m.rigid_mesh_contact_max = self.rigid_mesh_contact_max
|
|
4045
4306
|
m.rigid_contact_margin = self.rigid_contact_margin
|
|
4046
4307
|
m.rigid_contact_torsional_friction = self.rigid_contact_torsional_friction
|
|
4047
4308
|
m.rigid_contact_rolling_friction = self.rigid_contact_rolling_friction
|
|
4048
4309
|
|
|
4049
|
-
m.joint_dof_count = self.joint_dof_count
|
|
4050
|
-
m.joint_coord_count = self.joint_coord_count
|
|
4051
|
-
|
|
4052
|
-
# store refs to geometry
|
|
4053
|
-
m.geo_meshes = self.geo_meshes
|
|
4054
|
-
m.geo_sdfs = self.geo_sdfs
|
|
4055
|
-
|
|
4056
4310
|
# enable ground plane
|
|
4057
4311
|
m.ground_plane = wp.array(self._ground_params["plane"], dtype=wp.float32, requires_grad=requires_grad)
|
|
4058
4312
|
m.gravity = np.array(self.up_vector) * self.gravity
|