-
Notifications
You must be signed in to change notification settings - Fork 1.6k
/
Copy pathevents.py
1094 lines (925 loc) · 51.2 KB
/
events.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
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
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
# Copyright (c) 2022-2025, The Isaac Lab Project Developers.
# All rights reserved.
#
# SPDX-License-Identifier: BSD-3-Clause
"""Common functions that can be used to enable different events.
Events include anything related to altering the simulation state. This includes changing the physics
materials, applying external forces, and resetting the state of the asset.
The functions can be passed to the :class:`omni.isaac.lab.managers.EventTermCfg` object to enable
the event introduced by the function.
"""
from __future__ import annotations
import math
import torch
from typing import TYPE_CHECKING, Literal
import carb
import omni.physics.tensors.impl.api as physx
import omni.isaac.lab.sim as sim_utils
import omni.isaac.lab.utils.math as math_utils
from omni.isaac.lab.actuators import ImplicitActuator
from omni.isaac.lab.assets import Articulation, DeformableObject, RigidObject
from omni.isaac.lab.managers import EventTermCfg, ManagerTermBase, SceneEntityCfg
from omni.isaac.lab.terrains import TerrainImporter
if TYPE_CHECKING:
from omni.isaac.lab.envs import ManagerBasedEnv
class randomize_rigid_body_material(ManagerTermBase):
"""Randomize the physics materials on all geometries of the asset.
This function creates a set of physics materials with random static friction, dynamic friction, and restitution
values. The number of materials is specified by ``num_buckets``. The materials are generated by sampling
uniform random values from the given ranges.
The material properties are then assigned to the geometries of the asset. The assignment is done by
creating a random integer tensor of shape (num_instances, max_num_shapes) where ``num_instances``
is the number of assets spawned and ``max_num_shapes`` is the maximum number of shapes in the asset (over
all bodies). The integer values are used as indices to select the material properties from the
material buckets.
If the flag ``make_consistent`` is set to ``True``, the dynamic friction is set to be less than or equal to
the static friction. This obeys the physics constraint on friction values. However, it may not always be
essential for the application. Thus, the flag is set to ``False`` by default.
.. attention::
This function uses CPU tensors to assign the material properties. It is recommended to use this function
only during the initialization of the environment. Otherwise, it may lead to a significant performance
overhead.
.. note::
PhysX only allows 64000 unique physics materials in the scene. If the number of materials exceeds this
limit, the simulation will crash. Due to this reason, we sample the materials only once during initialization.
Afterwards, these materials are randomly assigned to the geometries of the asset.
"""
def __init__(self, cfg: EventTermCfg, env: ManagerBasedEnv):
"""Initialize the term.
Args:
cfg: The configuration of the event term.
env: The environment instance.
Raises:
ValueError: If the asset is not a RigidObject or an Articulation.
"""
super().__init__(cfg, env)
# extract the used quantities (to enable type-hinting)
self.asset_cfg: SceneEntityCfg = cfg.params["asset_cfg"]
self.asset: RigidObject | Articulation = env.scene[self.asset_cfg.name]
if not isinstance(self.asset, (RigidObject, Articulation)):
raise ValueError(
f"Randomization term 'randomize_rigid_body_material' not supported for asset: '{self.asset_cfg.name}'"
f" with type: '{type(self.asset)}'."
)
# obtain number of shapes per body (needed for indexing the material properties correctly)
# note: this is a workaround since the Articulation does not provide a direct way to obtain the number of shapes
# per body. We use the physics simulation view to obtain the number of shapes per body.
if isinstance(self.asset, Articulation) and self.asset_cfg.body_ids != slice(None):
self.num_shapes_per_body = []
for link_path in self.asset.root_physx_view.link_paths[0]:
link_physx_view = self.asset._physics_sim_view.create_rigid_body_view(link_path) # type: ignore
self.num_shapes_per_body.append(link_physx_view.max_shapes)
# ensure the parsing is correct
num_shapes = sum(self.num_shapes_per_body)
expected_shapes = self.asset.root_physx_view.max_shapes
if num_shapes != expected_shapes:
raise ValueError(
"Randomization term 'randomize_rigid_body_material' failed to parse the number of shapes per body."
f" Expected total shapes: {expected_shapes}, but got: {num_shapes}."
)
else:
# in this case, we don't need to do special indexing
self.num_shapes_per_body = None
# obtain parameters for sampling friction and restitution values
static_friction_range = cfg.params.get("static_friction_range", (1.0, 1.0))
dynamic_friction_range = cfg.params.get("dynamic_friction_range", (1.0, 1.0))
restitution_range = cfg.params.get("restitution_range", (0.0, 0.0))
num_buckets = int(cfg.params.get("num_buckets", 1))
# sample material properties from the given ranges
# note: we only sample the materials once during initialization
# afterwards these are randomly assigned to the geometries of the asset
range_list = [static_friction_range, dynamic_friction_range, restitution_range]
ranges = torch.tensor(range_list, device="cpu")
self.material_buckets = math_utils.sample_uniform(ranges[:, 0], ranges[:, 1], (num_buckets, 3), device="cpu")
# ensure dynamic friction is always less than static friction
make_consistent = cfg.params.get("make_consistent", False)
if make_consistent:
self.material_buckets[:, 1] = torch.min(self.material_buckets[:, 0], self.material_buckets[:, 1])
def __call__(
self,
env: ManagerBasedEnv,
env_ids: torch.Tensor | None,
static_friction_range: tuple[float, float],
dynamic_friction_range: tuple[float, float],
restitution_range: tuple[float, float],
num_buckets: int,
asset_cfg: SceneEntityCfg,
make_consistent: bool = False,
):
# resolve environment ids
if env_ids is None:
env_ids = torch.arange(env.scene.num_envs, device="cpu")
else:
env_ids = env_ids.cpu()
# randomly assign material IDs to the geometries
total_num_shapes = self.asset.root_physx_view.max_shapes
bucket_ids = torch.randint(0, num_buckets, (len(env_ids), total_num_shapes), device="cpu")
material_samples = self.material_buckets[bucket_ids]
# retrieve material buffer from the physics simulation
materials = self.asset.root_physx_view.get_material_properties()
# update material buffer with new samples
if self.num_shapes_per_body is not None:
# sample material properties from the given ranges
for body_id in self.asset_cfg.body_ids:
# obtain indices of shapes for the body
start_idx = sum(self.num_shapes_per_body[:body_id])
end_idx = start_idx + self.num_shapes_per_body[body_id]
# assign the new materials
# material samples are of shape: num_env_ids x total_num_shapes x 3
materials[env_ids, start_idx:end_idx] = material_samples[:, start_idx:end_idx]
else:
# assign all the materials
materials[env_ids] = material_samples[:]
# apply to simulation
self.asset.root_physx_view.set_material_properties(materials, env_ids)
class randomize_visual_texture_material(ManagerTermBase):
"""Randomize the visual texture of bodies on an asset using Replicator API.
This function randomizes the visual texture of the bodies of the asset using the Replicator API.
The function samples random textures from the given texture paths and applies them to the bodies
of the asset. The textures are projected onto the bodies and rotated by the given angles.
.. note::
The function assumes that the asset follows the prim naming convention as:
"{asset_prim_path}/{body_name}/visuals" where the body name is the name of the body to
which the texture is applied. This is the default prim ordering when importing assets
from the asset converters in Isaac Lab.
"""
def __init__(self, cfg: EventTermCfg, env: ManagerBasedEnv):
"""Initialize the term.
Args:
cfg: The configuration of the event term.
env: The environment instance.
"""
super().__init__(cfg, env)
# import replicator
# we import the module here since we may not always need the replicator
import omni.replicator.core as rep
# read parameters from the configuration
asset_cfg: SceneEntityCfg = cfg.params.get("asset_cfg")
texture_paths = cfg.params.get("texture_paths")
event_name = cfg.params.get("event_name")
texture_rotation = cfg.params.get("texture_rotation", (0.0, 0.0))
# check to make sure replicate_physics is set to False, else raise warning
if env.cfg.scene.replicate_physics:
raise ValueError(
"Unable to randomize visual texture material - ensure InteractiveSceneCfg's replicate_physics parameter"
" is set to False."
)
# convert from radians to degrees
texture_rotation = tuple(math.degrees(angle) for angle in texture_rotation)
# obtain the asset entity
asset_entity = env.scene[asset_cfg.name]
# join all bodies in the asset
body_names = asset_cfg.body_names
if isinstance(body_names, str):
body_names_regex = body_names
elif isinstance(body_names, list):
body_names_regex = "|".join(body_names)
else:
body_names_regex = ".*"
# Create the omni-graph node for the randomization term
def rep_texture_randomization():
prims_group = rep.get.prims(path_pattern=f"{asset_entity.cfg.prim_path}/{body_names_regex}/visuals")
with prims_group:
rep.randomizer.texture(
textures=texture_paths, project_uvw=True, texture_rotate=rep.distribution.uniform(*texture_rotation)
)
return prims_group.node
# Register the event to the replicator
with rep.trigger.on_custom_event(event_name=event_name):
rep_texture_randomization()
def __call__(
self,
env: ManagerBasedEnv,
env_ids: torch.Tensor,
event_name: str,
asset_cfg: SceneEntityCfg,
texture_paths: list[str],
texture_rotation: tuple[float, float] = (0.0, 0.0),
):
# import replicator
import omni.replicator.core as rep
# only send the event to the replicator
# note: This triggers the nodes for all the environments.
# We need to investigate how to make it happen only for a subset based on env_ids.
rep.utils.send_og_event(event_name)
def randomize_rigid_body_mass(
env: ManagerBasedEnv,
env_ids: torch.Tensor | None,
asset_cfg: SceneEntityCfg,
mass_distribution_params: tuple[float, float],
operation: Literal["add", "scale", "abs"],
distribution: Literal["uniform", "log_uniform", "gaussian"] = "uniform",
recompute_inertia: bool = True,
):
"""Randomize the mass of the bodies by adding, scaling, or setting random values.
This function allows randomizing the mass of the bodies of the asset. The function samples random values from the
given distribution parameters and adds, scales, or sets the values into the physics simulation based on the operation.
If the ``recompute_inertia`` flag is set to ``True``, the function recomputes the inertia tensor of the bodies
after setting the mass. This is useful when the mass is changed significantly, as the inertia tensor depends
on the mass. It assumes the body is a uniform density object. If the body is not a uniform density object,
the inertia tensor may not be accurate.
.. tip::
This function uses CPU tensors to assign the body masses. It is recommended to use this function
only during the initialization of the environment.
"""
# extract the used quantities (to enable type-hinting)
asset: RigidObject | Articulation = env.scene[asset_cfg.name]
# resolve environment ids
if env_ids is None:
env_ids = torch.arange(env.scene.num_envs, device="cpu")
else:
env_ids = env_ids.cpu()
# resolve body indices
if asset_cfg.body_ids == slice(None):
body_ids = torch.arange(asset.num_bodies, dtype=torch.int, device="cpu")
else:
body_ids = torch.tensor(asset_cfg.body_ids, dtype=torch.int, device="cpu")
# get the current masses of the bodies (num_assets, num_bodies)
masses = asset.root_physx_view.get_masses()
# apply randomization on default values
# this is to make sure when calling the function multiple times, the randomization is applied on the
# default values and not the previously randomized values
masses[env_ids[:, None], body_ids] = asset.data.default_mass[env_ids[:, None], body_ids].clone()
# sample from the given range
# note: we modify the masses in-place for all environments
# however, the setter takes care that only the masses of the specified environments are modified
masses = _randomize_prop_by_op(
masses, mass_distribution_params, env_ids, body_ids, operation=operation, distribution=distribution
)
# set the mass into the physics simulation
asset.root_physx_view.set_masses(masses, env_ids)
# recompute inertia tensors if needed
if recompute_inertia:
# compute the ratios of the new masses to the initial masses
ratios = masses[env_ids[:, None], body_ids] / asset.data.default_mass[env_ids[:, None], body_ids]
# scale the inertia tensors by the the ratios
# since mass randomization is done on default values, we can use the default inertia tensors
inertias = asset.root_physx_view.get_inertias()
if isinstance(asset, Articulation):
# inertia has shape: (num_envs, num_bodies, 9) for articulation
inertias[env_ids[:, None], body_ids] = (
asset.data.default_inertia[env_ids[:, None], body_ids] * ratios[..., None]
)
else:
# inertia has shape: (num_envs, 9) for rigid object
inertias[env_ids] = asset.data.default_inertia[env_ids] * ratios
# set the inertia tensors into the physics simulation
asset.root_physx_view.set_inertias(inertias, env_ids)
def randomize_physics_scene_gravity(
env: ManagerBasedEnv,
env_ids: torch.Tensor | None,
gravity_distribution_params: tuple[list[float], list[float]],
operation: Literal["add", "scale", "abs"],
distribution: Literal["uniform", "log_uniform", "gaussian"] = "uniform",
):
"""Randomize gravity by adding, scaling, or setting random values.
This function allows randomizing gravity of the physics scene. The function samples random values from the
given distribution parameters and adds, scales, or sets the values into the physics simulation based on the
operation.
The distribution parameters are lists of two elements each, representing the lower and upper bounds of the
distribution for the x, y, and z components of the gravity vector. The function samples random values for each
component independently.
.. attention::
This function applied the same gravity for all the environments.
.. tip::
This function uses CPU tensors to assign gravity.
"""
# get the current gravity
gravity = torch.tensor(env.sim.cfg.gravity, device="cpu").unsqueeze(0)
dist_param_0 = torch.tensor(gravity_distribution_params[0], device="cpu")
dist_param_1 = torch.tensor(gravity_distribution_params[1], device="cpu")
gravity = _randomize_prop_by_op(
gravity,
(dist_param_0, dist_param_1),
None,
slice(None),
operation=operation,
distribution=distribution,
)
# unbatch the gravity tensor into a list
gravity = gravity[0].tolist()
# set the gravity into the physics simulation
physics_sim_view: physx.SimulationView = sim_utils.SimulationContext.instance().physics_sim_view
physics_sim_view.set_gravity(carb.Float3(*gravity))
def randomize_actuator_gains(
env: ManagerBasedEnv,
env_ids: torch.Tensor | None,
asset_cfg: SceneEntityCfg,
stiffness_distribution_params: tuple[float, float] | None = None,
damping_distribution_params: tuple[float, float] | None = None,
operation: Literal["add", "scale", "abs"] = "abs",
distribution: Literal["uniform", "log_uniform", "gaussian"] = "uniform",
):
"""Randomize the actuator gains in an articulation by adding, scaling, or setting random values.
This function allows randomizing the actuator stiffness and damping gains.
The function samples random values from the given distribution parameters and applies the operation to the joint properties.
It then sets the values into the actuator models. If the distribution parameters are not provided for a particular property,
the function does not modify the property.
.. tip::
For implicit actuators, this function uses CPU tensors to assign the actuator gains into the simulation.
In such cases, it is recommended to use this function only during the initialization of the environment.
"""
# Extract the used quantities (to enable type-hinting)
asset: Articulation = env.scene[asset_cfg.name]
# Resolve environment ids
if env_ids is None:
env_ids = torch.arange(env.scene.num_envs, device=asset.device)
def randomize(data: torch.Tensor, params: tuple[float, float]) -> torch.Tensor:
return _randomize_prop_by_op(
data, params, dim_0_ids=None, dim_1_ids=actuator_indices, operation=operation, distribution=distribution
)
# Loop through actuators and randomize gains
for actuator in asset.actuators.values():
if isinstance(asset_cfg.joint_ids, slice):
# we take all the joints of the actuator
actuator_indices = slice(None)
if isinstance(actuator.joint_indices, slice):
global_indices = slice(None)
else:
global_indices = torch.tensor(actuator.joint_indices, device=asset.device)
elif isinstance(actuator.joint_indices, slice):
# we take the joints defined in the asset config
global_indices = actuator_indices = torch.tensor(asset_cfg.joint_ids, device=asset.device)
else:
# we take the intersection of the actuator joints and the asset config joints
actuator_joint_indices = torch.tensor(actuator.joint_indices, device=asset.device)
asset_joint_ids = torch.tensor(asset_cfg.joint_ids, device=asset.device)
# the indices of the joints in the actuator that have to be randomized
actuator_indices = torch.nonzero(torch.isin(actuator_joint_indices, asset_joint_ids)).view(-1)
if len(actuator_indices) == 0:
continue
# maps actuator indices that have to be randomized to global joint indices
global_indices = actuator_joint_indices[actuator_indices]
# Randomize stiffness
if stiffness_distribution_params is not None:
stiffness = actuator.stiffness[env_ids].clone()
stiffness[:, actuator_indices] = asset.data.default_joint_stiffness[env_ids][:, global_indices].clone()
randomize(stiffness, stiffness_distribution_params)
actuator.stiffness[env_ids] = stiffness
if isinstance(actuator, ImplicitActuator):
asset.write_joint_stiffness_to_sim(stiffness, joint_ids=actuator.joint_indices, env_ids=env_ids)
# Randomize damping
if damping_distribution_params is not None:
damping = actuator.damping[env_ids].clone()
damping[:, actuator_indices] = asset.data.default_joint_damping[env_ids][:, global_indices].clone()
randomize(damping, damping_distribution_params)
actuator.damping[env_ids] = damping
if isinstance(actuator, ImplicitActuator):
asset.write_joint_damping_to_sim(damping, joint_ids=actuator.joint_indices, env_ids=env_ids)
def randomize_joint_parameters(
env: ManagerBasedEnv,
env_ids: torch.Tensor | None,
asset_cfg: SceneEntityCfg,
friction_distribution_params: tuple[float, float] | None = None,
armature_distribution_params: tuple[float, float] | None = None,
lower_limit_distribution_params: tuple[float, float] | None = None,
upper_limit_distribution_params: tuple[float, float] | None = None,
operation: Literal["add", "scale", "abs"] = "abs",
distribution: Literal["uniform", "log_uniform", "gaussian"] = "uniform",
):
"""Randomize the joint parameters of an articulation by adding, scaling, or setting random values.
This function allows randomizing the joint parameters of the asset.
These correspond to the physics engine joint properties that affect the joint behavior.
The function samples random values from the given distribution parameters and applies the operation to the joint properties.
It then sets the values into the physics simulation. If the distribution parameters are not provided for a
particular property, the function does not modify the property.
.. tip::
This function uses CPU tensors to assign the joint properties. It is recommended to use this function
only during the initialization of the environment.
"""
# extract the used quantities (to enable type-hinting)
asset: Articulation = env.scene[asset_cfg.name]
# resolve environment ids
if env_ids is None:
env_ids = torch.arange(env.scene.num_envs, device=asset.device)
# resolve joint indices
if asset_cfg.joint_ids == slice(None):
joint_ids = slice(None) # for optimization purposes
else:
joint_ids = torch.tensor(asset_cfg.joint_ids, dtype=torch.int, device=asset.device)
# sample joint properties from the given ranges and set into the physics simulation
# -- friction
if friction_distribution_params is not None:
friction = asset.data.default_joint_friction.to(asset.device).clone()
friction = _randomize_prop_by_op(
friction, friction_distribution_params, env_ids, joint_ids, operation=operation, distribution=distribution
)[env_ids][:, joint_ids]
asset.write_joint_friction_to_sim(friction, joint_ids=joint_ids, env_ids=env_ids)
# -- armature
if armature_distribution_params is not None:
armature = asset.data.default_joint_armature.to(asset.device).clone()
armature = _randomize_prop_by_op(
armature, armature_distribution_params, env_ids, joint_ids, operation=operation, distribution=distribution
)[env_ids][:, joint_ids]
asset.write_joint_armature_to_sim(armature, joint_ids=joint_ids, env_ids=env_ids)
# -- dof limits
if lower_limit_distribution_params is not None or upper_limit_distribution_params is not None:
dof_limits = asset.data.default_joint_limits.to(asset.device).clone()
if lower_limit_distribution_params is not None:
lower_limits = dof_limits[..., 0]
lower_limits = _randomize_prop_by_op(
lower_limits,
lower_limit_distribution_params,
env_ids,
joint_ids,
operation=operation,
distribution=distribution,
)[env_ids][:, joint_ids]
dof_limits[env_ids[:, None], joint_ids, 0] = lower_limits
if upper_limit_distribution_params is not None:
upper_limits = dof_limits[..., 1]
upper_limits = _randomize_prop_by_op(
upper_limits,
upper_limit_distribution_params,
env_ids,
joint_ids,
operation=operation,
distribution=distribution,
)[env_ids][:, joint_ids]
dof_limits[env_ids[:, None], joint_ids, 1] = upper_limits
if (dof_limits[env_ids[:, None], joint_ids, 0] > dof_limits[env_ids[:, None], joint_ids, 1]).any():
raise ValueError(
"Randomization term 'randomize_joint_parameters' is setting lower joint limits that are greater than"
" upper joint limits."
)
asset.write_joint_limits_to_sim(dof_limits[env_ids][:, joint_ids], joint_ids=joint_ids, env_ids=env_ids)
def randomize_fixed_tendon_parameters(
env: ManagerBasedEnv,
env_ids: torch.Tensor | None,
asset_cfg: SceneEntityCfg,
stiffness_distribution_params: tuple[float, float] | None = None,
damping_distribution_params: tuple[float, float] | None = None,
limit_stiffness_distribution_params: tuple[float, float] | None = None,
lower_limit_distribution_params: tuple[float, float] | None = None,
upper_limit_distribution_params: tuple[float, float] | None = None,
rest_length_distribution_params: tuple[float, float] | None = None,
offset_distribution_params: tuple[float, float] | None = None,
operation: Literal["add", "scale", "abs"] = "abs",
distribution: Literal["uniform", "log_uniform", "gaussian"] = "uniform",
):
"""Randomize the fixed tendon parameters of an articulation by adding, scaling, or setting random values.
This function allows randomizing the fixed tendon parameters of the asset.
These correspond to the physics engine tendon properties that affect the joint behavior.
The function samples random values from the given distribution parameters and applies the operation to the tendon properties.
It then sets the values into the physics simulation. If the distribution parameters are not provided for a
particular property, the function does not modify the property.
"""
# extract the used quantities (to enable type-hinting)
asset: Articulation = env.scene[asset_cfg.name]
# resolve environment ids
if env_ids is None:
env_ids = torch.arange(env.scene.num_envs, device=asset.device)
# resolve joint indices
if asset_cfg.fixed_tendon_ids == slice(None):
fixed_tendon_ids = slice(None) # for optimization purposes
else:
fixed_tendon_ids = torch.tensor(asset_cfg.fixed_tendon_ids, dtype=torch.int, device=asset.device)
# sample tendon properties from the given ranges and set into the physics simulation
# -- stiffness
if stiffness_distribution_params is not None:
stiffness = asset.data.default_fixed_tendon_stiffness.clone()
stiffness = _randomize_prop_by_op(
stiffness,
stiffness_distribution_params,
env_ids,
fixed_tendon_ids,
operation=operation,
distribution=distribution,
)[env_ids][:, fixed_tendon_ids]
asset.set_fixed_tendon_stiffness(stiffness, fixed_tendon_ids, env_ids)
# -- damping
if damping_distribution_params is not None:
damping = asset.data.default_fixed_tendon_damping.clone()
damping = _randomize_prop_by_op(
damping,
damping_distribution_params,
env_ids,
fixed_tendon_ids,
operation=operation,
distribution=distribution,
)[env_ids][:, fixed_tendon_ids]
asset.set_fixed_tendon_damping(damping, fixed_tendon_ids, env_ids)
# -- limit stiffness
if limit_stiffness_distribution_params is not None:
limit_stiffness = asset.data.default_fixed_tendon_limit_stiffness.clone()
limit_stiffness = _randomize_prop_by_op(
limit_stiffness,
limit_stiffness_distribution_params,
env_ids,
fixed_tendon_ids,
operation=operation,
distribution=distribution,
)[env_ids][:, fixed_tendon_ids]
asset.set_fixed_tendon_limit_stiffness(limit_stiffness, fixed_tendon_ids, env_ids)
# -- limits
if lower_limit_distribution_params is not None or upper_limit_distribution_params is not None:
limit = asset.data.default_fixed_tendon_limit.clone()
# -- lower limit
if lower_limit_distribution_params is not None:
lower_limit = limit[..., 0]
lower_limit = _randomize_prop_by_op(
lower_limit,
lower_limit_distribution_params,
env_ids,
fixed_tendon_ids,
operation=operation,
distribution=distribution,
)[env_ids][:, fixed_tendon_ids]
limit[env_ids[:, None], fixed_tendon_ids, 0] = lower_limit
# -- upper limit
if upper_limit_distribution_params is not None:
upper_limit = limit[..., 1]
upper_limit = _randomize_prop_by_op(
upper_limit,
upper_limit_distribution_params,
env_ids,
fixed_tendon_ids,
operation=operation,
distribution=distribution,
)[env_ids][:, fixed_tendon_ids]
limit[env_ids[:, None], fixed_tendon_ids, 1] = upper_limit
if (limit[env_ids[:, None], fixed_tendon_ids, 0] > limit[env_ids[:, None], fixed_tendon_ids, 1]).any():
raise ValueError(
"Randomization term 'randomize_fixed_tendon_parameters' is setting lower tendon limits that are greater"
" than upper tendon limits."
)
asset.set_fixed_tendon_limit(limit, fixed_tendon_ids, env_ids)
# -- rest length
if rest_length_distribution_params is not None:
rest_length = asset.data.default_fixed_tendon_rest_length.clone()
rest_length = _randomize_prop_by_op(
rest_length,
rest_length_distribution_params,
env_ids,
fixed_tendon_ids,
operation=operation,
distribution=distribution,
)[env_ids][:, fixed_tendon_ids]
asset.set_fixed_tendon_rest_length(rest_length, fixed_tendon_ids, env_ids)
# -- offset
if offset_distribution_params is not None:
offset = asset.data.default_fixed_tendon_offset.clone()
offset = _randomize_prop_by_op(
offset,
offset_distribution_params,
env_ids,
fixed_tendon_ids,
operation=operation,
distribution=distribution,
)[env_ids][:, fixed_tendon_ids]
asset.set_fixed_tendon_offset(offset, fixed_tendon_ids, env_ids)
asset.write_fixed_tendon_properties_to_sim(fixed_tendon_ids, env_ids)
def apply_external_force_torque(
env: ManagerBasedEnv,
env_ids: torch.Tensor,
force_range: tuple[float, float],
torque_range: tuple[float, float],
asset_cfg: SceneEntityCfg = SceneEntityCfg("robot"),
):
"""Randomize the external forces and torques applied to the bodies.
This function creates a set of random forces and torques sampled from the given ranges. The number of forces
and torques is equal to the number of bodies times the number of environments. The forces and torques are
applied to the bodies by calling ``asset.set_external_force_and_torque``. The forces and torques are only
applied when ``asset.write_data_to_sim()`` is called in the environment.
"""
# extract the used quantities (to enable type-hinting)
asset: RigidObject | Articulation = env.scene[asset_cfg.name]
# resolve environment ids
if env_ids is None:
env_ids = torch.arange(env.scene.num_envs, device=asset.device)
# resolve number of bodies
num_bodies = len(asset_cfg.body_ids) if isinstance(asset_cfg.body_ids, list) else asset.num_bodies
# sample random forces and torques
size = (len(env_ids), num_bodies, 3)
forces = math_utils.sample_uniform(*force_range, size, asset.device)
torques = math_utils.sample_uniform(*torque_range, size, asset.device)
# set the forces and torques into the buffers
# note: these are only applied when you call: `asset.write_data_to_sim()`
asset.set_external_force_and_torque(forces, torques, env_ids=env_ids, body_ids=asset_cfg.body_ids)
def push_by_setting_velocity(
env: ManagerBasedEnv,
env_ids: torch.Tensor,
velocity_range: dict[str, tuple[float, float]],
asset_cfg: SceneEntityCfg = SceneEntityCfg("robot"),
):
"""Push the asset by setting the root velocity to a random value within the given ranges.
This creates an effect similar to pushing the asset with a random impulse that changes the asset's velocity.
It samples the root velocity from the given ranges and sets the velocity into the physics simulation.
The function takes a dictionary of velocity ranges for each axis and rotation. The keys of the dictionary
are ``x``, ``y``, ``z``, ``roll``, ``pitch``, and ``yaw``. The values are tuples of the form ``(min, max)``.
If the dictionary does not contain a key, the velocity is set to zero for that axis.
"""
# extract the used quantities (to enable type-hinting)
asset: RigidObject | Articulation = env.scene[asset_cfg.name]
# velocities
vel_w = asset.data.root_com_vel_w[env_ids]
# sample random velocities
range_list = [velocity_range.get(key, (0.0, 0.0)) for key in ["x", "y", "z", "roll", "pitch", "yaw"]]
ranges = torch.tensor(range_list, device=asset.device)
vel_w += math_utils.sample_uniform(ranges[:, 0], ranges[:, 1], vel_w.shape, device=asset.device)
# set the velocities into the physics simulation
asset.write_root_com_velocity_to_sim(vel_w, env_ids=env_ids)
def reset_root_state_uniform(
env: ManagerBasedEnv,
env_ids: torch.Tensor,
pose_range: dict[str, tuple[float, float]],
velocity_range: dict[str, tuple[float, float]],
asset_cfg: SceneEntityCfg = SceneEntityCfg("robot"),
):
"""Reset the asset root state to a random position and velocity uniformly within the given ranges.
This function randomizes the root position and velocity of the asset.
* It samples the root position from the given ranges and adds them to the default root position, before setting
them into the physics simulation.
* It samples the root orientation from the given ranges and sets them into the physics simulation.
* It samples the root velocity from the given ranges and sets them into the physics simulation.
The function takes a dictionary of pose and velocity ranges for each axis and rotation. The keys of the
dictionary are ``x``, ``y``, ``z``, ``roll``, ``pitch``, and ``yaw``. The values are tuples of the form
``(min, max)``. If the dictionary does not contain a key, the position or velocity is set to zero for that axis.
"""
# extract the used quantities (to enable type-hinting)
asset: RigidObject | Articulation = env.scene[asset_cfg.name]
# get default root state
root_states = asset.data.default_root_state[env_ids].clone()
# poses
range_list = [pose_range.get(key, (0.0, 0.0)) for key in ["x", "y", "z", "roll", "pitch", "yaw"]]
ranges = torch.tensor(range_list, device=asset.device)
rand_samples = math_utils.sample_uniform(ranges[:, 0], ranges[:, 1], (len(env_ids), 6), device=asset.device)
positions = root_states[:, 0:3] + env.scene.env_origins[env_ids] + rand_samples[:, 0:3]
orientations_delta = math_utils.quat_from_euler_xyz(rand_samples[:, 3], rand_samples[:, 4], rand_samples[:, 5])
orientations = math_utils.quat_mul(root_states[:, 3:7], orientations_delta)
# velocities
range_list = [velocity_range.get(key, (0.0, 0.0)) for key in ["x", "y", "z", "roll", "pitch", "yaw"]]
ranges = torch.tensor(range_list, device=asset.device)
rand_samples = math_utils.sample_uniform(ranges[:, 0], ranges[:, 1], (len(env_ids), 6), device=asset.device)
velocities = root_states[:, 7:13] + rand_samples
# set into the physics simulation
asset.write_root_link_pose_to_sim(torch.cat([positions, orientations], dim=-1), env_ids=env_ids)
asset.write_root_com_velocity_to_sim(velocities, env_ids=env_ids)
def reset_root_state_with_random_orientation(
env: ManagerBasedEnv,
env_ids: torch.Tensor,
pose_range: dict[str, tuple[float, float]],
velocity_range: dict[str, tuple[float, float]],
asset_cfg: SceneEntityCfg = SceneEntityCfg("robot"),
):
"""Reset the asset root position and velocities sampled randomly within the given ranges
and the asset root orientation sampled randomly from the SO(3).
This function randomizes the root position and velocity of the asset.
* It samples the root position from the given ranges and adds them to the default root position, before setting
them into the physics simulation.
* It samples the root orientation uniformly from the SO(3) and sets them into the physics simulation.
* It samples the root velocity from the given ranges and sets them into the physics simulation.
The function takes a dictionary of position and velocity ranges for each axis and rotation:
* :attr:`pose_range` - a dictionary of position ranges for each axis. The keys of the dictionary are ``x``,
``y``, and ``z``. The orientation is sampled uniformly from the SO(3).
* :attr:`velocity_range` - a dictionary of velocity ranges for each axis and rotation. The keys of the dictionary
are ``x``, ``y``, ``z``, ``roll``, ``pitch``, and ``yaw``.
The values are tuples of the form ``(min, max)``. If the dictionary does not contain a particular key,
the position is set to zero for that axis.
"""
# extract the used quantities (to enable type-hinting)
asset: RigidObject | Articulation = env.scene[asset_cfg.name]
# get default root state
root_states = asset.data.default_root_state[env_ids].clone()
# poses
range_list = [pose_range.get(key, (0.0, 0.0)) for key in ["x", "y", "z"]]
ranges = torch.tensor(range_list, device=asset.device)
rand_samples = math_utils.sample_uniform(ranges[:, 0], ranges[:, 1], (len(env_ids), 3), device=asset.device)
positions = root_states[:, 0:3] + env.scene.env_origins[env_ids] + rand_samples
orientations = math_utils.random_orientation(len(env_ids), device=asset.device)
# velocities
range_list = [velocity_range.get(key, (0.0, 0.0)) for key in ["x", "y", "z", "roll", "pitch", "yaw"]]
ranges = torch.tensor(range_list, device=asset.device)
rand_samples = math_utils.sample_uniform(ranges[:, 0], ranges[:, 1], (len(env_ids), 6), device=asset.device)
velocities = root_states[:, 7:13] + rand_samples
# set into the physics simulation
asset.write_root_link_pose_to_sim(torch.cat([positions, orientations], dim=-1), env_ids=env_ids)
asset.write_root_com_velocity_to_sim(velocities, env_ids=env_ids)
def reset_root_state_from_terrain(
env: ManagerBasedEnv,
env_ids: torch.Tensor,
pose_range: dict[str, tuple[float, float]],
velocity_range: dict[str, tuple[float, float]],
asset_cfg: SceneEntityCfg = SceneEntityCfg("robot"),
):
"""Reset the asset root state by sampling a random valid pose from the terrain.
This function samples a random valid pose(based on flat patches) from the terrain and sets the root state
of the asset to this position. The function also samples random velocities from the given ranges and sets them
into the physics simulation.
The function takes a dictionary of position and velocity ranges for each axis and rotation:
* :attr:`pose_range` - a dictionary of pose ranges for each axis. The keys of the dictionary are ``roll``,
``pitch``, and ``yaw``. The position is sampled from the flat patches of the terrain.
* :attr:`velocity_range` - a dictionary of velocity ranges for each axis and rotation. The keys of the dictionary
are ``x``, ``y``, ``z``, ``roll``, ``pitch``, and ``yaw``.
The values are tuples of the form ``(min, max)``. If the dictionary does not contain a particular key,
the position is set to zero for that axis.
Note:
The function expects the terrain to have valid flat patches under the key "init_pos". The flat patches
are used to sample the random pose for the robot.
Raises:
ValueError: If the terrain does not have valid flat patches under the key "init_pos".
"""
# access the used quantities (to enable type-hinting)
asset: RigidObject | Articulation = env.scene[asset_cfg.name]
terrain: TerrainImporter = env.scene.terrain
# obtain all flat patches corresponding to the valid poses
valid_positions: torch.Tensor = terrain.flat_patches.get("init_pos")
if valid_positions is None:
raise ValueError(
"The event term 'reset_root_state_from_terrain' requires valid flat patches under 'init_pos'."
f" Found: {list(terrain.flat_patches.keys())}"
)
# sample random valid poses
ids = torch.randint(0, valid_positions.shape[2], size=(len(env_ids),), device=env.device)
positions = valid_positions[terrain.terrain_levels[env_ids], terrain.terrain_types[env_ids], ids]
positions += asset.data.default_root_state[env_ids, :3]
# sample random orientations
range_list = [pose_range.get(key, (0.0, 0.0)) for key in ["roll", "pitch", "yaw"]]
ranges = torch.tensor(range_list, device=asset.device)
rand_samples = math_utils.sample_uniform(ranges[:, 0], ranges[:, 1], (len(env_ids), 3), device=asset.device)
# convert to quaternions
orientations = math_utils.quat_from_euler_xyz(rand_samples[:, 0], rand_samples[:, 1], rand_samples[:, 2])
# sample random velocities
range_list = [velocity_range.get(key, (0.0, 0.0)) for key in ["x", "y", "z", "roll", "pitch", "yaw"]]
ranges = torch.tensor(range_list, device=asset.device)
rand_samples = math_utils.sample_uniform(ranges[:, 0], ranges[:, 1], (len(env_ids), 6), device=asset.device)
velocities = asset.data.default_root_state[:, 7:13] + rand_samples
# set into the physics simulation
asset.write_root_link_pose_to_sim(torch.cat([positions, orientations], dim=-1), env_ids=env_ids)
asset.write_root_com_velocity_to_sim(velocities, env_ids=env_ids)
def reset_joints_by_scale(
env: ManagerBasedEnv,
env_ids: torch.Tensor,
position_range: tuple[float, float],
velocity_range: tuple[float, float],
asset_cfg: SceneEntityCfg = SceneEntityCfg("robot"),
):
"""Reset the robot joints by scaling the default position and velocity by the given ranges.
This function samples random values from the given ranges and scales the default joint positions and velocities
by these values. The scaled values are then set into the physics simulation.
"""
# extract the used quantities (to enable type-hinting)
asset: Articulation = env.scene[asset_cfg.name]
# get default joint state
joint_pos = asset.data.default_joint_pos[env_ids].clone()
joint_vel = asset.data.default_joint_vel[env_ids].clone()
# scale these values randomly
joint_pos *= math_utils.sample_uniform(*position_range, joint_pos.shape, joint_pos.device)
joint_vel *= math_utils.sample_uniform(*velocity_range, joint_vel.shape, joint_vel.device)
# clamp joint pos to limits
joint_pos_limits = asset.data.soft_joint_pos_limits[env_ids]
joint_pos = joint_pos.clamp_(joint_pos_limits[..., 0], joint_pos_limits[..., 1])
# clamp joint vel to limits
joint_vel_limits = asset.data.soft_joint_vel_limits[env_ids]
joint_vel = joint_vel.clamp_(-joint_vel_limits, joint_vel_limits)
# set into the physics simulation
asset.write_joint_state_to_sim(joint_pos, joint_vel, env_ids=env_ids)
def reset_joints_by_offset(
env: ManagerBasedEnv,
env_ids: torch.Tensor,
position_range: tuple[float, float],
velocity_range: tuple[float, float],
asset_cfg: SceneEntityCfg = SceneEntityCfg("robot"),
):
"""Reset the robot joints with offsets around the default position and velocity by the given ranges.
This function samples random values from the given ranges and biases the default joint positions and velocities
by these values. The biased values are then set into the physics simulation.
"""
# extract the used quantities (to enable type-hinting)
asset: Articulation = env.scene[asset_cfg.name]
# get default joint state
joint_pos = asset.data.default_joint_pos[env_ids].clone()
joint_vel = asset.data.default_joint_vel[env_ids].clone()
# bias these values randomly
joint_pos += math_utils.sample_uniform(*position_range, joint_pos.shape, joint_pos.device)
joint_vel += math_utils.sample_uniform(*velocity_range, joint_vel.shape, joint_vel.device)
# clamp joint pos to limits
joint_pos_limits = asset.data.soft_joint_pos_limits[env_ids]
joint_pos = joint_pos.clamp_(joint_pos_limits[..., 0], joint_pos_limits[..., 1])
# clamp joint vel to limits
joint_vel_limits = asset.data.soft_joint_vel_limits[env_ids]
joint_vel = joint_vel.clamp_(-joint_vel_limits, joint_vel_limits)
# set into the physics simulation
asset.write_joint_state_to_sim(joint_pos, joint_vel, env_ids=env_ids)
def reset_nodal_state_uniform(
env: ManagerBasedEnv,
env_ids: torch.Tensor,
position_range: dict[str, tuple[float, float]],
velocity_range: dict[str, tuple[float, float]],
asset_cfg: SceneEntityCfg = SceneEntityCfg("robot"),
):
"""Reset the asset nodal state to a random position and velocity uniformly within the given ranges.
This function randomizes the nodal position and velocity of the asset.
* It samples the root position from the given ranges and adds them to the default nodal position, before setting
them into the physics simulation.
* It samples the root velocity from the given ranges and sets them into the physics simulation.
The function takes a dictionary of position and velocity ranges for each axis. The keys of the
dictionary are ``x``, ``y``, ``z``. The values are tuples of the form ``(min, max)``.
If the dictionary does not contain a key, the position or velocity is set to zero for that axis.
"""
# extract the used quantities (to enable type-hinting)
asset: DeformableObject = env.scene[asset_cfg.name]
# get default root state
nodal_state = asset.data.default_nodal_state_w[env_ids].clone()
# position
range_list = [position_range.get(key, (0.0, 0.0)) for key in ["x", "y", "z"]]
ranges = torch.tensor(range_list, device=asset.device)
rand_samples = math_utils.sample_uniform(ranges[:, 0], ranges[:, 1], (len(env_ids), 1, 3), device=asset.device)
nodal_state[..., :3] += rand_samples
# velocities
range_list = [velocity_range.get(key, (0.0, 0.0)) for key in ["x", "y", "z"]]
ranges = torch.tensor(range_list, device=asset.device)
rand_samples = math_utils.sample_uniform(ranges[:, 0], ranges[:, 1], (len(env_ids), 1, 3), device=asset.device)
nodal_state[..., 3:] += rand_samples
# set into the physics simulation
asset.write_nodal_state_to_sim(nodal_state, env_ids=env_ids)
def reset_scene_to_default(env: ManagerBasedEnv, env_ids: torch.Tensor):
"""Reset the scene to the default state specified in the scene configuration."""
# rigid bodies
for rigid_object in env.scene.rigid_objects.values():