Skip to content

entity_prim

EntityPrim

Bases: XFormPrim

Provides high level functions to deal with an articulation prim and its attributes/ properties. Note that this type of prim cannot be created from scratch, and assumes there is already a pre-existing prim tree that should be converted into an articulation!

Parameters:

Name Type Description Default
prim_path str

prim path of the Prim to encapsulate or create.

required
name str

Name for the object. Names need to be unique per scene.

required
load_config None or dict

If specified, should contain keyword-mapped values that are relevant for loading this prim at runtime. Note that by default, this assumes an articulation already exists (i.e.: load() will raise NotImplementedError)! Subclasses must implement _load() for this prim to be able to be dynamically loaded after this class is created.

visual_only (None or bool): If specified, whether this prim should include collisions or not. Default is True.

None
Source code in omnigibson/prims/entity_prim.py
  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
1001
1002
1003
1004
1005
1006
1007
1008
1009
1010
1011
1012
1013
1014
1015
1016
1017
1018
1019
1020
1021
1022
1023
1024
1025
1026
1027
1028
1029
1030
1031
1032
1033
1034
1035
1036
1037
1038
1039
1040
1041
1042
1043
1044
1045
1046
1047
1048
1049
1050
1051
1052
1053
1054
1055
1056
1057
1058
1059
1060
1061
1062
1063
1064
1065
1066
1067
1068
1069
1070
1071
1072
1073
1074
1075
1076
1077
1078
1079
1080
1081
1082
1083
1084
1085
1086
1087
1088
1089
1090
1091
1092
1093
1094
1095
1096
1097
1098
1099
1100
1101
1102
1103
1104
1105
1106
1107
1108
1109
1110
1111
1112
1113
1114
1115
1116
1117
1118
1119
1120
1121
1122
1123
1124
1125
1126
1127
1128
1129
1130
1131
1132
1133
1134
1135
1136
1137
1138
1139
1140
1141
1142
1143
1144
1145
1146
1147
1148
1149
1150
1151
1152
1153
1154
1155
1156
1157
1158
1159
1160
1161
1162
1163
1164
1165
1166
1167
1168
1169
1170
1171
1172
1173
1174
1175
1176
1177
1178
1179
1180
1181
1182
1183
1184
1185
1186
1187
1188
1189
1190
1191
1192
1193
1194
1195
1196
1197
1198
1199
1200
1201
1202
1203
1204
1205
1206
1207
1208
1209
1210
1211
1212
1213
1214
1215
1216
1217
1218
1219
1220
1221
1222
1223
1224
1225
1226
1227
1228
1229
1230
1231
1232
1233
1234
1235
1236
1237
1238
1239
1240
1241
1242
1243
1244
1245
1246
1247
1248
1249
1250
1251
1252
1253
1254
1255
1256
1257
1258
1259
1260
1261
1262
1263
1264
1265
1266
1267
1268
1269
1270
1271
1272
1273
1274
1275
1276
1277
1278
1279
1280
1281
1282
1283
1284
1285
1286
1287
1288
1289
1290
1291
1292
1293
1294
1295
1296
1297
1298
1299
1300
1301
1302
1303
1304
1305
1306
1307
1308
1309
1310
1311
1312
1313
1314
1315
1316
1317
1318
1319
1320
1321
1322
1323
1324
1325
1326
1327
1328
1329
1330
1331
1332
1333
1334
1335
1336
1337
1338
1339
1340
1341
1342
1343
1344
1345
1346
1347
1348
1349
1350
1351
1352
1353
1354
1355
1356
1357
1358
1359
1360
1361
1362
1363
1364
1365
1366
1367
1368
1369
1370
1371
1372
1373
1374
1375
1376
1377
1378
1379
1380
1381
1382
1383
1384
1385
1386
1387
1388
1389
1390
1391
1392
1393
1394
1395
1396
1397
1398
1399
1400
1401
1402
1403
1404
1405
1406
1407
1408
1409
1410
class EntityPrim(XFormPrim):
    """
    Provides high level functions to deal with an articulation prim and its attributes/ properties. Note that this
    type of prim cannot be created from scratch, and assumes there is already a pre-existing prim tree that should
    be converted into an articulation!

    Args:
        prim_path (str): prim path of the Prim to encapsulate or create.
        name (str): Name for the object. Names need to be unique per scene.
        load_config (None or dict): If specified, should contain keyword-mapped values that are relevant for
            loading this prim at runtime. Note that by default, this assumes an articulation already exists (i.e.:
            load() will raise NotImplementedError)! Subclasses must implement _load() for this prim to be able to be
            dynamically loaded after this class is created.

            visual_only (None or bool): If specified, whether this prim should include collisions or not.
                    Default is True.
        """

    def __init__(
        self,
        prim_path,
        name,
        load_config=None,
    ):
        # Other values that will be filled in at runtime
        self._dc = None                         # Dynamics control interface
        self._handle = None                     # Handle to this articulation
        self._root_handle = None                # Handle to the root rigid body of this articulation
        self._root_link_name = None             # Name of the root link
        self._dofs_infos = None
        self._n_dof = None                      # dof with dynamic control
        self._links = None
        self._joints = None
        self._materials = None
        self._visual_only = None

        # This needs to be initialized to be used for _load() of PrimitiveObject
        self._prim_type = load_config["prim_type"] if load_config is not None and "prim_type" in load_config else PrimType.RIGID
        assert self._prim_type in iter(PrimType), f"Unknown prim type {self._prim_type}!"

        # Run super init
        super().__init__(
            prim_path=prim_path,
            name=name,
            load_config=load_config,
        )

    def _initialize(self):
        # Run super method
        super()._initialize()

        # Force populate inputs and outputs of the shaders of all materials
        # We suppress errors from omni.hydra if we're using encrypted assets, because we're loading from tmp location,
        # not the original location
        with suppress_omni_log(channels=["omni.hydra"]):
            for material in self.materials:
                material.shader_force_populate(render=False)

        # Initialize all the links
        # This must happen BEFORE the handle is generated for this prim, because things changing in the RigidPrims may
        # cause the handle to change!
        for link in self._links.values():
            link.initialize()

        # Get dynamic control info
        self._dc = _dynamic_control.acquire_dynamic_control_interface()

        # Update joint information
        self.update_joints()

    def _load(self):
        # By default, this prim cannot be instantiated from scratch!
        raise NotImplementedError("By default, an entity prim cannot be created from scratch.")

    def _post_load(self):
        # If this is a cloth, delete the root link and replace it with the single nested mesh
        if self._prim_type == PrimType.CLOTH:
            # Verify only a single link and a single mesh exists
            old_link_prim = None
            cloth_mesh_prim = None
            for prim in self._prim.GetChildren():
                if prim.GetPrimTypeInfo().GetTypeName() == "Xform":
                    assert old_link_prim is None, "Found multiple XForm links for a Cloth entity prim! Expected: 1"
                    old_link_prim = prim
                    for child in prim.GetChildren():
                        if child.GetPrimTypeInfo().GetTypeName() == "Mesh" and not child.HasAPI(UsdPhysics.CollisionAPI):
                            assert cloth_mesh_prim is None, "Found multiple meshes for a Cloth entity prim! Expected: 1"
                            cloth_mesh_prim = child

            # Move mesh prim one level up via copy, then delete the original link
            # NOTE: We copy because we cannot directly move the prim because it is ancestral
            # NOTE: We use this specific delete method because alternative methods (eg: "delete_prim") fail beacuse
            # the prim is ancestral. Note that because it is non-destructive, the original link prim path is still
            # tracked by omni, so we have to utilize a new unique prim path for the copied cloth mesh
            # See omni.kit.context_menu module for reference
            new_path = f"{self._prim_path}/{old_link_prim.GetName()}_cloth"
            omni.kit.commands.execute("CopyPrim", path_from=cloth_mesh_prim.GetPath(), path_to=new_path)
            omni.kit.commands.execute("DeletePrims", paths=[old_link_prim.GetPath()], destructive=False)

        # Setup links info FIRST before running any other post loading behavior
        # We pass in scale explicitly so that the generated links can leverage the desired entity scale
        self.update_links(load_config=dict(scale=self._load_config.get("scale", None)))

        # Set visual only flag
        # This automatically handles setting collisions / gravity appropriately per-link
        self.visual_only = self._load_config["visual_only"] if \
            "visual_only" in self._load_config and self._load_config["visual_only"] is not None else False

        if self._prim_type == PrimType.CLOTH:
            assert not self._visual_only, "Cloth cannot be visual-only."
            assert len(self._links) == 1, f"Cloth entity prim can only have one link; got: {len(self._links)}"
            if gm.AG_CLOTH:
                self.create_attachment_point_link()

        # Globally disable any requested collision links
        for link_name in self.disabled_collision_link_names:
            self._links[link_name].disable_collisions()

        # Disable any requested collision pairs
        for a_name, b_name in self.disabled_collision_pairs:
            link_a, link_b = self._links[a_name], self._links[b_name]
            link_a.add_filtered_collision_pair(prim=link_b)

        # Run super
        super()._post_load()

        # Cache material information
        materials = set()
        material_paths = set()
        for link in self._links.values():
            xforms = [link] + list(link.visual_meshes.values()) if self.prim_type == PrimType.RIGID else [link]
            for xform in xforms:
                if xform.has_material():
                    mat_path = xform.material.prim_path
                    if mat_path not in material_paths:
                        materials.add(xform.material)
                        material_paths.add(mat_path)

        self._materials = materials

    def update_links(self, load_config=None):
        """
        Helper function to refresh owned joints. Useful for synchronizing internal data if
        additional bodies are added manually

        Args:
            load_config (None or dict): If specified, should contain keyword-mapped values that are relevant for
            loading each of the link's rigid prims
        """
        # Make sure to clean up all pre-existing names for all links
        if self._links is not None:
            for link in self._links.values():
                link.remove_names()

        # We iterate over all children of this object's prim,
        # and grab any that are presumed to be rigid bodies (i.e.: other Xforms)
        self._links = dict()
        joint_children = set()
        for prim in self._prim.GetChildren():
            link_cls = None
            link_name = prim.GetName()
            if self._prim_type == PrimType.RIGID and prim.GetPrimTypeInfo().GetTypeName() == "Xform":
                # For rigid body object, process prims that are Xforms (e.g. rigid links)
                link_cls = RigidPrim
                # Also iterate through all children to infer joints and determine the children of those joints
                # We will use this info to infer which link is the base link!
                for child_prim in prim.GetChildren():
                    if "joint" in child_prim.GetPrimTypeInfo().GetTypeName().lower():
                        # Store the child target of this joint
                        relationships = {r.GetName(): r for r in child_prim.GetRelationships()}
                        # Only record if this is NOT a fixed link tying us to the world (i.e.: no target for body0)
                        if len(relationships["physics:body0"].GetTargets()) > 0:
                            joint_children.add(relationships["physics:body1"].GetTargets()[0].pathString.split("/")[-1])

            elif self._prim_type == PrimType.CLOTH and prim.GetPrimTypeInfo().GetTypeName() == "Mesh":
                # For cloth object, process prims that are Meshes
                link_cls = ClothPrim

            if link_cls is not None:
                self._links[link_name] = link_cls(
                    prim_path=prim.GetPrimPath().__str__(),
                    name=f"{self._name}:{link_name}",
                    load_config=load_config,
                )

        # Infer the correct root link name -- this corresponds to whatever link does not have any joint existing
        # in the children joints
        valid_root_links = list(set(self._links.keys()) - joint_children)

        # TODO: Uncomment safety check here after we figure out how to handle legacy multi-bodied assets like bed with pillow
        # assert len(valid_root_links) == 1, f"Only a single root link should have been found for this entity prim, " \
        #                                    f"but found multiple instead: {valid_root_links}"
        self._root_link_name = valid_root_links[0] if len(valid_root_links) == 1 else "base_link"

    def update_joints(self):
        """
        Helper function to refresh owned joints. Useful for synchronizing internal data if
        additional bodies are added manually
        """
        # Make sure to clean up all pre-existing names for all joints
        if self._joints is not None:
            for joint in self._joints.values():
                joint.remove_names()

        # Initialize joints dictionary
        self._joints = dict()
        self.update_handles()

        # Handle case separately based on whether the handle is valid (i.e.: whether we are actually articulated or not)
        if (not self.kinematic_only) and self._handle is not None:
            root_prim = get_prim_at_path(self._dc.get_rigid_body_path(self._root_handle))
            n_dof = self._dc.get_articulation_dof_count(self._handle)

            # Additionally grab DOF info if we have non-fixed joints
            if n_dof > 0:
                self._dofs_infos = dict()
                # Grab DOF info
                for index in range(n_dof):
                    dof_handle = self._dc.get_articulation_dof(self._handle, index)
                    dof_name = self._dc.get_dof_name(dof_handle)
                    # add dof to list
                    prim_path = self._dc.get_dof_path(dof_handle)
                    self._dofs_infos[dof_name] = DOFInfo(prim_path=prim_path, handle=dof_handle, prim=self.prim,
                                                         index=index)

                for i in range(self._dc.get_articulation_joint_count(self._handle)):
                    joint_handle = self._dc.get_articulation_joint(self._handle, i)
                    joint_name = self._dc.get_joint_name(joint_handle)
                    joint_path = self._dc.get_joint_path(joint_handle)
                    joint_prim = get_prim_at_path(joint_path)
                    # Only add the joint if it's not fixed (i.e.: it has DOFs > 0)
                    if self._dc.get_joint_dof_count(joint_handle) > 0:
                        joint = JointPrim(
                            prim_path=joint_path,
                            name=f"{self._name}:joint_{joint_name}",
                            articulation=self._handle,
                        )
                        joint.initialize()
                        self._joints[joint_name] = joint
        else:
            # TODO: May need to extend to clusters of rigid bodies, that aren't exactly joined
            # We assume this object contains a single rigid body
            body_path = f"{self._prim_path}/{self.root_link_name}"
            root_prim = get_prim_at_path(body_path)
            n_dof = 0

        # Make sure root prim stored is the same as the one found during initialization
        assert self.root_prim == root_prim, \
            f"Mismatch in root prims! Original was {self.root_prim.GetPrimPath()}, " \
            f"initialized is {root_prim.GetPrimPath()}!"

        # Store values internally
        self._n_dof = n_dof
        self._update_joint_limits()

    def _update_joint_limits(self):
        """
        Helper function to update internal joint limits for prismatic joints based on the object's scale
        """
        # If the scale is [1, 1, 1], we can skip this step
        if np.allclose(self.scale, np.ones(3)):
            return

        prismatic_joints = {j_name: j for j_name, j in self._joints.items() if j.joint_type == JointType.JOINT_PRISMATIC}

        # If there are no prismatic joints, we can skip this step
        if len(prismatic_joints) == 0:
            return

        uniform_scale = np.allclose(self.scale, self.scale[0])

        for joint_name, joint in prismatic_joints.items():
            if uniform_scale:
                scale_along_axis = self.scale[0]
            else:
                assert not self.initialized, \
                    "Cannot update joint limits for a non-uniformly scaled object when already initialized."
                for link_name, link in self.links.items():
                    if joint.parent_name == link_name:
                        # Find the parent link frame orientation in the object frame
                        _, link_local_orn = link.get_local_pose()

                        # Find the joint frame orientation in the parent link frame
                        joint_local_orn = gf_quat_to_np_array(joint.get_attribute("physics:localRot0"))[[1, 2, 3, 0]]

                        # Compute the joint frame orientation in the object frame
                        joint_orn = T.quat_multiply(quaternion1=joint_local_orn, quaternion0=link_local_orn)

                        # assert T.check_quat_right_angle(joint_orn), \
                        #     f"Objects that are NOT uniformly scaled requires all joints to have orientations that " \
                        #     f"are factors of 90 degrees! Got orn: {joint_orn} for object {self.name}"

                        # Find the joint axis unit vector (e.g. [1, 0, 0] for "X", [0, 1, 0] for "Y", etc.)
                        axis_in_joint_frame = np.zeros(3)
                        axis_in_joint_frame[JointAxis.index(joint.axis)] = 1.0

                        # Compute the joint axis unit vector in the object frame
                        axis_in_obj_frame = T.quat2mat(joint_orn) @ axis_in_joint_frame

                        # Find the correct scale along the joint axis direction
                        scale_along_axis = self.scale[np.argmax(np.abs(axis_in_obj_frame))]

            joint.lower_limit = joint.lower_limit * scale_along_axis
            joint.upper_limit = joint.upper_limit * scale_along_axis

    @property
    def prim_type(self):
        """
        Returns:
            str: Type of this entity prim, one of omnigibson.utils.constants.PrimType
        """
        return self._prim_type

    @property
    def articulated(self):
        """
        Returns:
             bool: Whether this prim is articulated or not
        """
        # An invalid handle implies that there is no articulation available for this object
        return self._handle is not None or self.articulation_root_path is not None

    @property
    def articulation_root_path(self):
        """
        Returns:
            None or str: Absolute USD path to the expected prim that represents the articulation root, if it exists. By default,
                this corresponds to self.prim_path
        """
        return self._prim_path if self.n_joints > 0 else None

    @property
    def root_link_name(self):
        """
        Returns:
            str: Name of this entity's root link
        """
        return self._root_link_name

    @property
    def root_link(self):
        """
        Returns:
            RigidPrim or ClothPrim: Root link of this object prim
        """
        return self._links[self.root_link_name]

    @property
    def root_prim(self):
        """
        Returns:
            UsdPrim: Root prim object associated with the root link of this object prim
        """
        # The root prim belongs to the link with name root_link_name
        return self._links[self.root_link_name].prim

    @property
    def handle(self):
        """
        Returns:
            None or int: ID (articulation) handle assigned to this prim from dynamic_control interface. Note that
                if this prim is not an articulation, it is None
        """
        return self._handle

    @property
    def root_handle(self):
        """
        Handle used by Isaac Sim's dynamic control module to reference the root body in this object.
        Note: while self.handle may be 0 (i.e.: invalid articulation, i.e.: object with no joints), root_handle should
            always be non-zero (i.e.: valid) if this object is initialized!

        Returns:
            int: ID handle assigned to this prim's root prim from dynamic_control interface
        """
        return self._root_handle

    @property
    def n_dof(self):
        """
        Returns:
            int: number of DoFs of the object
        """
        return self._n_dof

    @property
    def n_joints(self):
        """
        Returns:
            int: Number of joints owned by this articulation
        """
        if self.initialized:
            num = len(list(self._joints.keys()))
        else:
            # Manually iterate over all links and check for any joints that are not fixed joints!
            num = 0
            for link in self._links.values():
                for child_prim in link.prim.GetChildren():
                    prim_type = child_prim.GetPrimTypeInfo().GetTypeName().lower()
                    if "joint" in prim_type and "fixed" not in prim_type:
                        num += 1
        return num

    @property
    def n_fixed_joints(self):
        """
        Returns:
        int: Number of fixed joints owned by this articulation
        """
        # Manually iterate over all links and check for any joints that are not fixed joints!
        num = 0
        for link in self._links.values():
            for child_prim in link.prim.GetChildren():
                prim_type = child_prim.GetPrimTypeInfo().GetTypeName().lower()
                if "joint" in prim_type and "fixed" in prim_type:
                    num += 1

        return num

    @property
    def n_links(self):
        """
        Returns:
            int: Number of links owned by this articulation
        """
        return len(list(self._links.keys()))

    @property
    def joints(self):
        """
        Returns:
            dict: Dictionary mapping joint names (str) to joint prims (JointPrim) owned by this articulation
        """
        return self._joints

    @property
    def links(self):
        """
        Returns:
            dict: Dictionary mapping link names (str) to link prims (RigidPrim) owned by this articulation
        """
        return self._links

    @property
    def materials(self):
        """
        Loop through each link and their visual meshes to gather all the materials that belong to this object

        Returns:
            set of MaterialPrim: a set of MaterialPrim that belongs to this object
        """
        return self._materials

    @property
    def dof_properties(self):
        """
        Returns:
            n-array: Array of DOF properties assigned to this articulation's DoFs.
        """
        return self._dc.get_articulation_dof_properties(self._handle)

    @property
    def visual_only(self):
        """
        Returns:
            bool: Whether this link is a visual-only link (i.e.: no gravity or collisions applied)
        """
        return self._visual_only

    @visual_only.setter
    def visual_only(self, val):
        """
        Sets the visaul only state of this link

        Args:
            val (bool): Whether this link should be a visual-only link (i.e.: no gravity or collisions applied)
        """
        # Iterate over all owned links and set their respective visual-only properties accordingly
        for link in self._links.values():
            link.visual_only = val

        # Also set the internal value
        self._visual_only = val

    def contact_list(self):
        """
        Get list of all current contacts with this object prim

        Returns:
            list of CsRawData: raw contact info for this rigid body
        """
        contacts = []
        for link in self._links.values():
            contacts += link.contact_list()
        return contacts

    def enable_gravity(self) -> None:
        """
        Enables gravity for this entity
        """
        for link in self._links.values():
            link.enable_gravity()

    def disable_gravity(self) -> None:
        """
        Disables gravity for this entity
        """
        for link in self._links.values():
            link.disable_gravity()

    def set_joint_positions(self, positions, indices=None, normalized=False, drive=False):
        """
        Set the joint positions (both actual value and target values) in simulation. Note: only works if the simulator
        is actively running!

        Args:
            positions (np.ndarray): positions to set. This should be n-DOF length if all joints are being set,
                or k-length (k < n) if specific indices are being set. In this case, the length of @positions must
                be the same length as @indices!
            indices (None or k-array): If specified, should be k (k < n) length array of specific DOF positions to set.
                Default is None, which assumes that all joints are being set.
            normalized (bool): Whether the inputted joint positions should be interpreted as normalized values. Default
                is False
            drive (bool): Whether the positions being set are values that should be driven naturally by this entity's
                motors or manual values to immediately set. Default is False, corresponding to an instantaneous
                setting of the positions
        """
        # Run sanity checks -- make sure our handle is initialized and that we are articulated
        assert self._handle is not None, "handles are not initialized yet!"
        assert self.n_joints > 0, "Tried to call method not intended for entity prim with no joints!"

        # Possibly de-normalize the inputs
        if normalized:
            positions = self._denormalize_positions(positions=positions, indices=indices)

        # Grab current DOF states
        dof_states = self._dc.get_articulation_dof_states(self._handle, _dynamic_control.STATE_POS)

        # Possibly set specific values in the array if indies are specified
        if indices is None:
            assert len(positions) == self._n_dof, \
                "set_joint_positions called without specifying indices, but the desired positions do not match n_dof."
            new_positions = positions
        else:
            new_positions = dof_states["pos"]
            new_positions[indices] = positions

        # Set the DOF states
        dof_states["pos"] = new_positions
        if not drive:
            self._dc.set_articulation_dof_states(self._handle, dof_states, _dynamic_control.STATE_POS)
            BoundingBoxAPI.clear()

        # Also set the target
        self._dc.set_articulation_dof_position_targets(self._handle, new_positions.astype(np.float32))

    def set_joint_velocities(self, velocities, indices=None, normalized=False, drive=False):
        """
        Set the joint velocities (both actual value and target values) in simulation. Note: only works if the simulator
        is actively running!

        Args:
            velocities (np.ndarray): velocities to set. This should be n-DOF length if all joints are being set,
                or k-length (k < n) if specific indices are being set. In this case, the length of @velocities must
                be the same length as @indices!
            indices (None or k-array): If specified, should be k (k < n) length array of specific DOF velocities to set.
                Default is None, which assumes that all joints are being set.
            normalized (bool): Whether the inputted joint velocities should be interpreted as normalized values. Default
                is False
            drive (bool): Whether the velocities being set are values that should be driven naturally by this entity's
                motors or manual values to immediately set. Default is False, corresponding to an instantaneous
                setting of the velocities
        """
        # Run sanity checks -- make sure our handle is initialized and that we are articulated
        assert self._handle is not None, "handles are not initialized yet!"
        assert self.n_joints > 0, "Tried to call method not intended for entity prim with no joints!"

        # Possibly de-normalize the inputs
        if normalized:
            velocities = self._denormalize_velocities(velocities=velocities, indices=indices)

        # Grab current DOF states
        dof_states = self._dc.get_articulation_dof_states(self._handle, _dynamic_control.STATE_VEL)

        # Possibly set specific values in the array if indies are specified
        if indices is None:
            new_velocities = velocities
        else:
            new_velocities = dof_states["vel"]
            new_velocities[indices] = velocities

        # Set the DOF states
        dof_states["vel"] = new_velocities
        if not drive:
            self._dc.set_articulation_dof_states(self._handle, dof_states, _dynamic_control.STATE_VEL)

        # Also set the target
        self._dc.set_articulation_dof_velocity_targets(self._handle, new_velocities.astype(np.float32))

    def set_joint_efforts(self, efforts, indices=None, normalized=False):
        """
        Set the joint efforts (both actual value and target values) in simulation. Note: only works if the simulator
        is actively running!

        Args:
            efforts (np.ndarray): efforts to set. This should be n-DOF length if all joints are being set,
                or k-length (k < n) if specific indices are being set. In this case, the length of @efforts must
                be the same length as @indices!
            indices (None or k-array): If specified, should be k (k < n) length array of specific DOF efforts to set.
                Default is None, which assumes that all joints are being set.
            normalized (bool): Whether the inputted joint efforts should be interpreted as normalized values. Default
                is False
        """
        # Run sanity checks -- make sure our handle is initialized and that we are articulated
        assert self._handle is not None, "handles are not initialized yet!"
        assert self.n_joints > 0, "Tried to call method not intended for entity prim with no joints!"

        # Possibly de-normalize the inputs
        if normalized:
            efforts = self._denormalize_efforts(efforts=efforts, indices=indices)

        # Grab current DOF states
        dof_states = self._dc.get_articulation_dof_states(self._handle, _dynamic_control.STATE_EFFORT)

        # Possibly set specific values in the array if indies are specified
        if indices is None:
            new_efforts = efforts
        else:
            new_efforts = dof_states["effort"]
            new_efforts[indices] = efforts

        # Set the DOF states
        dof_states["effort"] = new_efforts
        self._dc.set_articulation_dof_states(self._handle, dof_states, _dynamic_control.STATE_EFFORT)

    def _normalize_positions(self, positions, indices=None):
        """
        Normalizes raw joint positions @positions

        Args:
            positions (n- or k-array): n-DOF raw positions to normalize, or k (k < n) specific positions to normalize.
                In the latter case, @indices should be specified
            indices (None or k-array): If specified, should be k (k < n) DOF indices corresponding to the specific
                positions to normalize. Default is None, which assumes the positions correspond to all DOF being
                normalized.

        Returns:
            n- or k-array: normalized positions in range [-1, 1] for the specified DOFs
        """
        low, high = self.joint_lower_limits, self.joint_upper_limits
        mean = (low + high) / 2.0
        magnitude = (high - low) / 2.0
        return (positions - mean) / magnitude if indices is None else (positions - mean[indices]) / magnitude[indices]

    def _denormalize_positions(self, positions, indices=None):
        """
        De-normalizes joint positions @positions

        Args:
            positions (n- or k-array): n-DOF normalized positions or k (k < n) specific positions in range [-1, 1]
                to de-normalize. In the latter case, @indices should be specified
            indices (None or k-array): If specified, should be k (k < n) DOF indices corresponding to the specific
                positions to de-normalize. Default is None, which assumes the positions correspond to all DOF being
                de-normalized.

        Returns:
            n- or k-array: de-normalized positions for the specified DOFs
        """
        low, high = self.joint_lower_limits, self.joint_upper_limits
        mean = (low + high) / 2.0
        magnitude = (high - low) / 2.0
        return positions * magnitude + mean if indices is None else positions * magnitude[indices] + mean[indices]

    def _normalize_velocities(self, velocities, indices=None):
        """
        Normalizes raw joint velocities @velocities

        Args:
            velocities (n- or k-array): n-DOF raw velocities to normalize, or k (k < n) specific velocities to normalize.
                In the latter case, @indices should be specified
            indices (None or k-array): If specified, should be k (k < n) DOF indices corresponding to the specific
                velocities to normalize. Default is None, which assumes the velocities correspond to all DOF being
                normalized.

        Returns:
            n- or k-array: normalized velocities in range [-1, 1] for the specified DOFs
        """
        return velocities / self.max_joint_velocities if indices is None else \
            velocities / self.max_joint_velocities[indices]

    def _denormalize_velocities(self, velocities, indices=None):
        """
        De-normalizes joint velocities @velocities

        Args:
            velocities (n- or k-array): n-DOF normalized velocities or k (k < n) specific velocities in range [-1, 1]
                to de-normalize. In the latter case, @indices should be specified
            indices (None or k-array): If specified, should be k (k < n) DOF indices corresponding to the specific
                velocities to de-normalize. Default is None, which assumes the velocities correspond to all DOF being
                de-normalized.

        Returns:
            n- or k-array: de-normalized velocities for the specified DOFs
        """
        return velocities * self.max_joint_velocities if indices is None else \
            velocities * self.max_joint_velocities[indices]

    def _normalize_efforts(self, efforts, indices=None):
        """
        Normalizes raw joint efforts @efforts

        Args:
            efforts (n- or k-array): n-DOF raw efforts to normalize, or k (k < n) specific efforts to normalize.
                In the latter case, @indices should be specified
            indices (None or k-array): If specified, should be k (k < n) DOF indices corresponding to the specific
                efforts to normalize. Default is None, which assumes the efforts correspond to all DOF being
                normalized.

        Returns:
            n- or k-array: normalized efforts in range [-1, 1] for the specified DOFs
        """
        return efforts / self.max_joint_efforts if indices is None else efforts / self.max_joint_efforts[indices]

    def _denormalize_efforts(self, efforts, indices=None):
        """
        De-normalizes joint efforts @efforts

        Args:
            efforts (n- or k-array): n-DOF normalized efforts or k (k < n) specific efforts in range [-1, 1]
                to de-normalize. In the latter case, @indices should be specified
            indices (None or k-array): If specified, should be k (k < n) DOF indices corresponding to the specific
                efforts to de-normalize. Default is None, which assumes the efforts correspond to all DOF being
                de-normalized.

        Returns:
            n- or k-array: de-normalized efforts for the specified DOFs
        """
        return efforts * self.max_joint_efforts if indices is None else efforts * self.max_joint_efforts[indices]

    def update_handles(self):
        """
        Updates all internal handles for this prim, in case they change since initialization
        """
        assert og.sim.is_playing(), "Simulator must be playing if updating handles!"

        # Grab the handle -- we know it might not return a valid value, so we suppress omni's warning here
        self._handle = None if self.articulation_root_path is None else \
            self._dc.get_articulation(self.articulation_root_path)

        # Sanity check -- make sure handle is not invalid handle -- it should only ever be None or a valid integer
        assert self._handle != _dynamic_control.INVALID_HANDLE, \
            f"Got invalid articulation handle for entity at {self.articulation_root_path}"

        # We only have a root handle if we're not a cloth prim
        if self._prim_type != PrimType.CLOTH:
            self._root_handle = self._dc.get_articulation_root_body(self._handle) if \
                self._handle is not None else self.root_link.handle

        # Update all links and joints as well
        for link in self._links.values():
            if not link.initialized:
                link.initialize()
            link.update_handles()

        for joint in self._joints.values():
            if not joint.initialized:
                joint.initialize()
            joint.update_handles()

    def get_joint_positions(self, normalized=False):
        """
        Grabs this entity's joint positions

        Args:
            normalized (bool): Whether returned values should be normalized to range [-1, 1] based on limits or not.

        Returns:
            n-array: n-DOF length array of positions
        """
        # Run sanity checks -- make sure our handle is initialized and that we are articulated
        assert self._handle is not None, "handles are not initialized yet!"
        assert self.n_joints > 0, "Tried to call method not intended for entity prim with no joints!"

        joint_positions = self._dc.get_articulation_dof_states(self._handle, _dynamic_control.STATE_POS)["pos"]

        # Possibly normalize values when returning
        return self._normalize_positions(positions=joint_positions) if normalized else joint_positions

    def get_joint_velocities(self, normalized=False):
        """
        Grabs this entity's joint velocities

        Args:
            normalized (bool): Whether returned values should be normalized to range [-1, 1] based on limits or not.

        Returns:
            n-array: n-DOF length array of velocities
        """
        # Run sanity checks -- make sure our handle is initialized and that we are articulated
        assert self._handle is not None, "handles are not initialized yet!"
        assert self.n_joints > 0, "Tried to call method not intended for entity prim with no joints!"

        joint_velocities = self._dc.get_articulation_dof_states(self._handle, _dynamic_control.STATE_VEL)["vel"]

        # Possibly normalize values when returning
        return self._normalize_velocities(velocities=joint_velocities) if normalized else joint_velocities

    def get_joint_efforts(self, normalized=False):
        """
        Grabs this entity's joint efforts

        Args:
            normalized (bool): Whether returned values should be normalized to range [-1, 1] based on limits or not.

        Returns:
            n-array: n-DOF length array of efforts
        """
        # Run sanity checks -- make sure our handle is initialized and that we are articulated
        assert self._handle is not None, "handles are not initialized yet!"
        assert self.n_joints > 0, "Tried to call method not intended for entity prim with no joints!"

        joint_efforts = self._dc.get_articulation_dof_states(self._handle, _dynamic_control.STATE_EFFORT)["effort"]

        # Possibly normalize values when returning
        return self._normalize_efforts(efforts=joint_efforts) if normalized else joint_efforts

    def set_linear_velocity(self, velocity: np.ndarray):
        """
        Sets the linear velocity of the root prim in stage.

        Args:
            velocity (np.ndarray): linear velocity to set the rigid prim to, in the world frame. Shape (3,).
        """
        self.root_link.set_linear_velocity(velocity)

    def get_linear_velocity(self):
        """
        Gets the linear velocity of the root prim in stage.

        Returns:
            velocity (np.ndarray): linear velocity to set the rigid prim to, in the world frame. Shape (3,).
        """
        return self.root_link.get_linear_velocity()

    def set_angular_velocity(self, velocity):
        """
        Sets the angular velocity of the root prim in stage.

        Args:
            velocity (np.ndarray): angular velocity to set the rigid prim to, in the world frame. Shape (3,).
        """
        self.root_link.set_angular_velocity(velocity)

    def get_angular_velocity(self):
        """Gets the angular velocity of the root prim in stage.

        Returns:
            velocity (np.ndarray): angular velocity to set the rigid prim to, in the world frame. Shape (3,).
        """
        return self.root_link.get_angular_velocity()

    def set_position_orientation(self, position=None, orientation=None):
        current_position, current_orientation = self.get_position_orientation()
        if position is None:
            position = current_position
        if orientation is None:
            orientation = current_orientation

        if self._prim_type == PrimType.CLOTH:
            if self._dc is not None and self._dc.is_simulating():
                self.root_link.set_position_orientation(position, orientation)
            else:
                super().set_position_orientation(position, orientation)
        else:
            if self._root_handle is not None and self._root_handle != _dynamic_control.INVALID_HANDLE and \
                    self._dc is not None and self._dc.is_simulating():
                self.root_link.set_position_orientation(position, orientation)
            else:
                super().set_position_orientation(position=position, orientation=orientation)

        BoundingBoxAPI.clear()

    def get_position_orientation(self):
        if self._prim_type == PrimType.CLOTH:
            if self._dc is not None and self._dc.is_simulating():
                return self.root_link.get_position_orientation()
            else:
                return super().get_position_orientation()
        else:
            if self._root_handle is not None and self._root_handle != _dynamic_control.INVALID_HANDLE and \
                    self._dc is not None and self._dc.is_simulating():
                return self.root_link.get_position_orientation()
            else:
                return super().get_position_orientation()

    def _set_local_pose_when_simulating(self, translation=None, orientation=None):
        """
        Sets prim's pose with respect to the local frame (the prim's parent frame) when simulation is running.

        Args:
            translation (None or 3-array): if specified, (x,y,z) translation in the local frame of the prim
                (with respect to its parent prim). Default is None, which means left unchanged.
            orientation (None or 4-array): if specified, (x,y,z,w) quaternion orientation in the local frame of the prim
                (with respect to its parent prim). Default is None, which means left unchanged.
        """
        current_translation, current_orientation = self.get_local_pose()
        if translation is None:
            translation = current_translation
        if orientation is None:
            orientation = current_orientation
        orientation = orientation[[3, 0, 1, 2]]
        local_transform = tf_matrix_from_pose(translation=translation, orientation=orientation)
        parent_world_tf = UsdGeom.Xformable(get_prim_parent(self._prim)).ComputeLocalToWorldTransform(
            Usd.TimeCode.Default()
        )
        my_world_transform = np.matmul(parent_world_tf, local_transform)
        transform = Gf.Transform()
        transform.SetMatrix(Gf.Matrix4d(np.transpose(my_world_transform)))
        calculated_position = transform.GetTranslation()
        calculated_orientation = transform.GetRotation().GetQuat()
        self.set_position_orientation(
            position=np.array(calculated_position),
            orientation=gf_quat_to_np_array(calculated_orientation)[[1, 2, 3, 0]],
        )

    def set_local_pose(self, translation=None, orientation=None):
        if self._prim_type == PrimType.CLOTH:
            if self._dc is not None and self._dc.is_simulating():
                self._set_local_pose_when_simulating(translation=translation, orientation=orientation)
            else:
                super().set_local_pose(translation=translation, orientation=orientation)
        else:
            if self._root_handle is not None and self._root_handle != _dynamic_control.INVALID_HANDLE and \
                    self._dc is not None and self._dc.is_simulating():
                self._set_local_pose_when_simulating(translation=translation, orientation=orientation)
            else:
                super().set_local_pose(translation=translation, orientation=orientation)
        BoundingBoxAPI.clear()

    def _get_local_pose_when_simulating(self):
        """
        Gets prim's pose with respect to the prim's local frame (it's parent frame) when simulation is running

        Returns:
            2-tuple:
                - 3-array: (x,y,z) position in the local frame
                - 4-array: (x,y,z,w) quaternion orientation in the local frame
        """
        parent_world_tf = UsdGeom.Xformable(get_prim_parent(self._prim)).ComputeLocalToWorldTransform(
            Usd.TimeCode.Default()
        )
        world_position, world_orientation = self.get_position_orientation()
        my_world_transform = tf_matrix_from_pose(translation=world_position,
                                                 orientation=world_orientation[[3, 0, 1, 2]])
        local_transform = np.matmul(np.linalg.inv(np.transpose(parent_world_tf)), my_world_transform)
        transform = Gf.Transform()
        transform.SetMatrix(Gf.Matrix4d(np.transpose(local_transform)))
        calculated_translation = transform.GetTranslation()
        calculated_orientation = transform.GetRotation().GetQuat()
        return np.array(calculated_translation), gf_quat_to_np_array(calculated_orientation)[[1, 2, 3, 0]]

    def get_local_pose(self):
        if self._prim_type == PrimType.CLOTH:
            if self._dc is not None and self._dc.is_simulating():
                return self._get_local_pose_when_simulating()
            else:
                return super().get_local_pose()
        else:
            if self._root_handle is not None and self._root_handle != _dynamic_control.INVALID_HANDLE and \
                    self._dc is not None and self._dc.is_simulating():
                return self._get_local_pose_when_simulating()
            else:
                return super().get_local_pose()

    # TODO: Is the omni joint damping (used for driving motors) same as dissipative joint damping (what we had in pb)?
    @property
    def joint_damping(self):
        """
        Returns:
            n-array: joint damping values for this prim
        """
        return np.concatenate([joint.damping for joint in self._joints.values()])

    @property
    def joint_lower_limits(self):
        """
        Returns:
            n-array: minimum values for this robot's joints. If joint does not have a range, returns -1000
                for that joint
        """
        return np.array([joint.lower_limit for joint in self._joints.values()])

    @property
    def joint_upper_limits(self):
        """
        Returns:
            n-array: maximum values for this robot's joints. If joint does not have a range, returns 1000
                for that joint
        """
        return np.array([joint.upper_limit for joint in self._joints.values()])

    @property
    def joint_range(self):
        """
        Returns:
            n-array: joint range values for this robot's joints
        """
        return self.joint_upper_limits - self.joint_lower_limits

    @property
    def max_joint_velocities(self):
        """
        Returns:
            n-array: maximum velocities for this robot's joints
        """
        return np.array([joint.max_velocity for joint in self._joints.values()])

    @property
    def max_joint_efforts(self):
        """
        Returns:
            n-array: maximum efforts for this robot's joints
        """
        return np.array([joint.max_effort for joint in self._joints.values()])

    @property
    def joint_position_limits(self):
        """
        Returns:
            2-tuple:
                - n-array: min joint position limits, where each is an n-DOF length array
                - n-array: max joint position limits, where each is an n-DOF length array
        """
        return self.joint_lower_limits, self.joint_upper_limits

    @property
    def joint_velocity_limits(self):
        """
        Returns:
            2-tuple:
                - n-array: min joint velocity limits, where each is an n-DOF length array
                - n-array: max joint velocity limits, where each is an n-DOF length array
        """
        return -self.max_joint_velocities, self.max_joint_velocities

    @property
    def joint_effort_limits(self):
        """
        Returns:
            2-tuple:
                - n-array: min joint effort limits, where each is an n-DOF length array
                - n-array: max joint effort limits, where each is an n-DOF length array
        """
        return -self.max_joint_efforts, self.max_joint_efforts

    @property
    def joint_at_limits(self):
        """
        Returns:
            n-array: n-DOF length array specifying whether joint is at its limit,
                with 1.0 --> at limit, otherwise 0.0
        """
        return 1.0 * (np.abs(self.get_joint_positions(normalized=True)) > 0.99)

    @property
    def joint_has_limits(self):
        """
        Returns:
            n-array: n-DOF length array specifying whether joint has a limit or not
        """
        return np.array([j.has_limit for j in self._joints.values()])

    @property
    def disabled_collision_link_names(self):
        """
        Returns:
            list of str: List of link names for this entity whose collisions should be globally disabled
        """
        return []

    @property
    def disabled_collision_pairs(self):
        """
        Returns:
            list of (str, str): List of rigid body collision pairs to disable within this object prim.
                Default is an empty list (no pairs)
        """
        return []

    @property
    def scale(self):
        # Since all rigid bodies owned by this object prim have the same scale, we simply grab it from the root prim
        return self.root_link.scale

    @scale.setter
    def scale(self, scale):
        # We iterate over all rigid bodies owned by this object prim and set their individual scales
        # We do this because omniverse cannot scale orientation of an articulated prim, so we get mesh mismatches as
        # they rotate in the world
        for link in self._links.values():
            link.scale = scale

    @property
    def solver_position_iteration_count(self):
        """
        Returns:
            int: How many position iterations to take per physics step by the physx solver
        """
        return get_prim_property(self.articulation_root_path, "physxArticulation:solverPositionIterationCount") if \
            self.articulated else self.root_link.solver_position_iteration_count

    @solver_position_iteration_count.setter
    def solver_position_iteration_count(self, count):
        """
        Sets how many position iterations to take per physics step by the physx solver

        Args:
            count (int): How many position iterations to take per physics step by the physx solver
        """
        if self.articulated:
            set_prim_property(self.articulation_root_path, "physxArticulation:solverPositionIterationCount", count)
        else:
            for link in self._links.values():
                link.solver_position_iteration_count = count

    @property
    def solver_velocity_iteration_count(self):
        """
        Returns:
            int: How many velocity iterations to take per physics step by the physx solver
        """
        return get_prim_property(self.articulation_root_path, "physxArticulation:solverVelocityIterationCount") if \
            self.articulated else self.root_link.solver_velocity_iteration_count

    @solver_velocity_iteration_count.setter
    def solver_velocity_iteration_count(self, count):
        """
        Sets how many velocity iterations to take per physics step by the physx solver

        Args:
            count (int): How many velocity iterations to take per physics step by the physx solver
        """
        if self.articulated:
            set_prim_property(self.articulation_root_path, "physxArticulation:solverVelocityIterationCount", count)
        else:
            for link in self._links.values():
                link.solver_velocity_iteration_count = count

    @property
    def stabilization_threshold(self):
        """
        Returns:
            float: threshold for stabilizing this articulation
        """
        return get_prim_property(self.articulation_root_path, "physxArticulation:stabilizationThreshold") if \
            self.articulated else self.root_link.stabilization_threshold

    @stabilization_threshold.setter
    def stabilization_threshold(self, threshold):
        """
        Sets threshold for stabilizing this articulation

        Args:
            threshold (float): Stabilization threshold
        """
        if self.articulated:
            set_prim_property(self.articulation_root_path, "physxArticulation:stabilizationThreshold", threshold)
        else:
            for link in self._links.values():
                link.stabilization_threshold = threshold

    @property
    def sleep_threshold(self):
        """
        Returns:
            float: threshold for sleeping this articulation
        """
        return get_prim_property(self.articulation_root_path, "physxArticulation:sleepThreshold") if \
            self.articulated else self.root_link.sleep_threshold

    @sleep_threshold.setter
    def sleep_threshold(self, threshold):
        """
        Sets threshold for sleeping this articulation

        Args:
            threshold (float): Sleeping threshold
        """
        if self.articulated:
            set_prim_property(self.articulation_root_path, "physxArticulation:sleepThreshold", threshold)
        else:
            for link in self._links.values():
                link.sleep_threshold = threshold

    @property
    def self_collisions(self):
        """
        Returns:
            bool: Whether self-collisions are enabled for this prim or not
        """
        assert self.articulated, "Cannot get self-collision for non-articulated EntityPrim!"
        return get_prim_property(self.articulation_root_path, "physxArticulation:enabledSelfCollisions")

    @self_collisions.setter
    def self_collisions(self, flag):
        """
        Sets whether self-collisions are enabled for this prim or not

        Args:
            flag (bool): Whether self collisions are enabled for this prim or not
        """
        assert self.articulated, "Cannot set self-collision for non-articulated EntityPrim!"
        set_prim_property(self.articulation_root_path, "physxArticulation:enabledSelfCollisions", flag)

    @property
    def kinematic_only(self):
        """
        Returns:
            bool: Whether this object is a kinematic-only object (otherwise, it is a rigid body). A kinematic-only
                object is not subject to simulator dynamics, and remains fixed unless the user explicitly sets the
                body's pose / velocities. See https://docs.omniverse.nvidia.com/app_create/prod_extensions/ext_physics/rigid-bodies.html?highlight=rigid%20body%20enabled#kinematic-rigid-bodies
                for more information
        """
        return self.root_link.kinematic_only

    @kinematic_only.setter
    def kinematic_only(self, val):
        """
        Args:
            val (bool): Whether this object is a kinematic-only object (otherwise, it is a rigid body). A kinematic-only
                object is not subject to simulator dynamics, and remains fixed unless the user explicitly sets the
                body's pose / velocities. See https://docs.omniverse.nvidia.com/app_create/prod_extensions/ext_physics/rigid-bodies.html?highlight=rigid%20body%20enabled#kinematic-rigid-bodies
                for more information
        """
        self.root_link.kinematic_only = val

    @property
    def aabb(self):
        # If we're a cloth prim type, we compute the bounding box from the limits of the particles. Otherwise, use the
        # normal method for computing bounding box
        if self._prim_type == PrimType.CLOTH:
            particle_contact_offset = self.root_link.cloth_system.particle_contact_offset
            particle_positions = self.root_link.compute_particle_positions()
            aabb_lo, aabb_hi = np.min(particle_positions, axis=0) - particle_contact_offset, \
                               np.max(particle_positions, axis=0) + particle_contact_offset
        else:
            aabb_lo, aabb_hi = super().aabb
            aabb_lo, aabb_hi = np.array(aabb_lo), np.array(aabb_hi)

        return aabb_lo, aabb_hi

    def wake(self):
        """
        Enable physics for this articulation
        """
        if self.articulated:
            self._dc.wake_up_articulation(self._handle)
        else:
            for link in self._links.values():
                link.wake()

    def sleep(self):
        """
        Disable physics for this articulation
        """
        if self.articulated:
            self._dc.sleep_articulation(self._handle)
        else:
            for link in self._links.values():
                link.sleep()

    def keep_still(self):
        """
        Zero out all velocities for this prim
        """
        self.set_linear_velocity(velocity=np.zeros(3))
        self.set_angular_velocity(velocity=np.zeros(3))
        for joint in self._joints.values():
            joint.keep_still()
        # Make sure object is awake
        self.wake()

    def create_attachment_point_link(self):
        """
        Create a collision-free, invisible attachment point link for the cloth object, and create an attachment between
        the ClothPrim and this attachment point link (RigidPrim).

        One use case for this is that we can create a fixed joint between this link and the world to enable AG fo cloth.
        During simulation, this joint will move and match the robot gripper frame, which will then drive the cloth.
        """

        assert self._prim_type == PrimType.CLOTH, "create_attachment_point_link should only be called for Cloth"
        link_name = "attachment_point"
        stage = get_current_stage()
        link_prim = stage.DefinePrim(f"{self._prim_path}/{link_name}", "Xform")
        vis_prim = UsdGeom.Sphere.Define(stage, f"{self._prim_path}/{link_name}/visuals").GetPrim()
        col_prim = UsdGeom.Sphere.Define(stage, f"{self._prim_path}/{link_name}/collisions").GetPrim()

        # Set the radius to be 0.03m. In theory, we want this radius to be as small as possible. Otherwise, the cloth
        # dynamics will be unrealistic. However, in practice, if the radius is too small, the attachment becomes very
        # unstable. Empirically 0.03m works reasonably well.
        vis_prim.GetAttribute("radius").Set(0.03)
        col_prim.GetAttribute("radius").Set(0.03)

        # Need to sync the extents
        extent = vis_prim.GetAttribute("extent").Get()
        extent[0] = Gf.Vec3f(-0.03, -0.03, -0.03)
        extent[1] = Gf.Vec3f(0.03, 0.03, 0.03)
        vis_prim.GetAttribute("extent").Set(extent)
        col_prim.GetAttribute("extent").Set(extent)

        # Add collision API to collision geom
        UsdPhysics.CollisionAPI.Apply(col_prim)
        UsdPhysics.MeshCollisionAPI.Apply(col_prim)
        PhysxSchema.PhysxCollisionAPI.Apply(col_prim)

        # Create a attachment point link
        link = RigidPrim(
            prim_path=link_prim.GetPrimPath().__str__(),
            name=f"{self._name}:{link_name}",
        )
        link.disable_collisions()
        # TODO (eric): Should we disable gravity for this link?
        # link.disable_gravity()
        link.visible = False
        # Set a very small mass
        link.mass = 1e-6

        self._links[link_name] = link

        # Create an attachment between the root link (ClothPrim) and the newly created attachment point link (RigidPrim)
        attachment_path = self.root_link.prim.GetPath().AppendElementString("attachment")
        omni.kit.commands.execute("CreatePhysicsAttachment", target_attachment_path=attachment_path,
                                  actor0_path=self.root_link.prim.GetPath(), actor1_path=link.prim.GetPath())

    def _dump_state(self):
        # We don't call super, instead, this state is simply the root link state and all joint states
        state = dict(root_link=self.root_link._dump_state())
        joint_state = dict()
        for prim_name, prim in self._joints.items():
            joint_state[prim_name] = prim._dump_state()
        state["joints"] = joint_state

        return state

    def _load_state(self, state):
        # Load base link state and joint states
        self.root_link._load_state(state=state["root_link"])
        for joint_name, joint_state in state["joints"].items():
            self._joints[joint_name]._load_state(state=joint_state)

        # Make sure this object is awake
        self.wake()

    def _serialize(self, state):
        # We serialize by first flattening the root link state and then iterating over all joints and
        # adding them to the a flattened array
        state_flat = [self.root_link.serialize(state=state["root_link"])]
        if self.n_joints > 0:
            state_flat.append(
                np.concatenate(
                    [prim.serialize(state=state["joints"][prim_name]) for prim_name, prim in self._joints.items()]
                )
            )

        return np.concatenate(state_flat).astype(float)

    def _deserialize(self, state):
        # We deserialize by first de-flattening the root link state and then iterating over all joints and
        # sequentially grabbing from the flattened state array, incrementing along the way
        idx = self.root_link.state_size
        state_dict = dict(root_link=self.root_link.deserialize(state=state[:idx]))
        joint_state_dict = dict()
        for prim_name, prim in self._joints.items():
            joint_state_dict[prim_name] = prim.deserialize(state=state[idx:idx+prim.state_size])
            idx += prim.state_size
        state_dict["joints"] = joint_state_dict

        return state_dict, idx

    def _create_prim_with_same_kwargs(self, prim_path, name, load_config):
        # Subclass must implement this method for duplication functionality
        raise NotImplementedError("Subclass must implement _create_prim_with_same_kwargs() to enable duplication "
                                  "functionality for EntityPrim!")

articulated property

Returns:

Name Type Description
bool

Whether this prim is articulated or not

articulation_root_path property

Returns:

Type Description

None or str: Absolute USD path to the expected prim that represents the articulation root, if it exists. By default, this corresponds to self.prim_path

Returns:

Type Description

list of str: List of link names for this entity whose collisions should be globally disabled

disabled_collision_pairs property

Returns:

Type Description

list of (str, str): List of rigid body collision pairs to disable within this object prim. Default is an empty list (no pairs)

dof_properties property

Returns:

Type Description

n-array: Array of DOF properties assigned to this articulation's DoFs.

handle property

Returns:

Type Description

None or int: ID (articulation) handle assigned to this prim from dynamic_control interface. Note that if this prim is not an articulation, it is None

joint_at_limits property

Returns:

Type Description

n-array: n-DOF length array specifying whether joint is at its limit, with 1.0 --> at limit, otherwise 0.0

joint_damping property

Returns:

Type Description

n-array: joint damping values for this prim

joint_effort_limits property

Returns:

Type Description

2-tuple: - n-array: min joint effort limits, where each is an n-DOF length array - n-array: max joint effort limits, where each is an n-DOF length array

joint_has_limits property

Returns:

Type Description

n-array: n-DOF length array specifying whether joint has a limit or not

joint_lower_limits property

Returns:

Type Description

n-array: minimum values for this robot's joints. If joint does not have a range, returns -1000 for that joint

joint_position_limits property

Returns:

Type Description

2-tuple: - n-array: min joint position limits, where each is an n-DOF length array - n-array: max joint position limits, where each is an n-DOF length array

joint_range property

Returns:

Type Description

n-array: joint range values for this robot's joints

joint_upper_limits property

Returns:

Type Description

n-array: maximum values for this robot's joints. If joint does not have a range, returns 1000 for that joint

joint_velocity_limits property

Returns:

Type Description

2-tuple: - n-array: min joint velocity limits, where each is an n-DOF length array - n-array: max joint velocity limits, where each is an n-DOF length array

joints property

Returns:

Name Type Description
dict

Dictionary mapping joint names (str) to joint prims (JointPrim) owned by this articulation

kinematic_only writable property

Returns:

Name Type Description
bool

Whether this object is a kinematic-only object (otherwise, it is a rigid body). A kinematic-only object is not subject to simulator dynamics, and remains fixed unless the user explicitly sets the body's pose / velocities. See https://docs.omniverse.nvidia.com/app_create/prod_extensions/ext_physics/rigid-bodies.html?highlight=rigid%20body%20enabled#kinematic-rigid-bodies for more information

Returns:

Name Type Description
dict

Dictionary mapping link names (str) to link prims (RigidPrim) owned by this articulation

materials property

Loop through each link and their visual meshes to gather all the materials that belong to this object

Returns:

Type Description

set of MaterialPrim: a set of MaterialPrim that belongs to this object

max_joint_efforts property

Returns:

Type Description

n-array: maximum efforts for this robot's joints

max_joint_velocities property

Returns:

Type Description

n-array: maximum velocities for this robot's joints

n_dof property

Returns:

Name Type Description
int

number of DoFs of the object

n_fixed_joints property

int: Number of fixed joints owned by this articulation

n_joints property

Returns:

Name Type Description
int

Number of joints owned by this articulation

Returns:

Name Type Description
int

Number of links owned by this articulation

prim_type property

Returns:

Name Type Description
str

Type of this entity prim, one of omnigibson.utils.constants.PrimType

root_handle property

Handle used by Isaac Sim's dynamic control module to reference the root body in this object.

while self.handle may be 0 (i.e.: invalid articulation, i.e.: object with no joints), root_handle should

always be non-zero (i.e.: valid) if this object is initialized!

Returns:

Name Type Description
int

ID handle assigned to this prim's root prim from dynamic_control interface

Returns:

Type Description

RigidPrim or ClothPrim: Root link of this object prim

Returns:

Name Type Description
str

Name of this entity's root link

root_prim property

Returns:

Name Type Description
UsdPrim

Root prim object associated with the root link of this object prim

self_collisions writable property

Returns:

Name Type Description
bool

Whether self-collisions are enabled for this prim or not

sleep_threshold writable property

Returns:

Name Type Description
float

threshold for sleeping this articulation

solver_position_iteration_count writable property

Returns:

Name Type Description
int

How many position iterations to take per physics step by the physx solver

solver_velocity_iteration_count writable property

Returns:

Name Type Description
int

How many velocity iterations to take per physics step by the physx solver

stabilization_threshold writable property

Returns:

Name Type Description
float

threshold for stabilizing this articulation

visual_only writable property

Returns:

Name Type Description
bool

Whether this link is a visual-only link (i.e.: no gravity or collisions applied)

contact_list()

Get list of all current contacts with this object prim

Returns:

Type Description

list of CsRawData: raw contact info for this rigid body

Source code in omnigibson/prims/entity_prim.py
def contact_list(self):
    """
    Get list of all current contacts with this object prim

    Returns:
        list of CsRawData: raw contact info for this rigid body
    """
    contacts = []
    for link in self._links.values():
        contacts += link.contact_list()
    return contacts

Create a collision-free, invisible attachment point link for the cloth object, and create an attachment between the ClothPrim and this attachment point link (RigidPrim).

One use case for this is that we can create a fixed joint between this link and the world to enable AG fo cloth. During simulation, this joint will move and match the robot gripper frame, which will then drive the cloth.

Source code in omnigibson/prims/entity_prim.py
def create_attachment_point_link(self):
    """
    Create a collision-free, invisible attachment point link for the cloth object, and create an attachment between
    the ClothPrim and this attachment point link (RigidPrim).

    One use case for this is that we can create a fixed joint between this link and the world to enable AG fo cloth.
    During simulation, this joint will move and match the robot gripper frame, which will then drive the cloth.
    """

    assert self._prim_type == PrimType.CLOTH, "create_attachment_point_link should only be called for Cloth"
    link_name = "attachment_point"
    stage = get_current_stage()
    link_prim = stage.DefinePrim(f"{self._prim_path}/{link_name}", "Xform")
    vis_prim = UsdGeom.Sphere.Define(stage, f"{self._prim_path}/{link_name}/visuals").GetPrim()
    col_prim = UsdGeom.Sphere.Define(stage, f"{self._prim_path}/{link_name}/collisions").GetPrim()

    # Set the radius to be 0.03m. In theory, we want this radius to be as small as possible. Otherwise, the cloth
    # dynamics will be unrealistic. However, in practice, if the radius is too small, the attachment becomes very
    # unstable. Empirically 0.03m works reasonably well.
    vis_prim.GetAttribute("radius").Set(0.03)
    col_prim.GetAttribute("radius").Set(0.03)

    # Need to sync the extents
    extent = vis_prim.GetAttribute("extent").Get()
    extent[0] = Gf.Vec3f(-0.03, -0.03, -0.03)
    extent[1] = Gf.Vec3f(0.03, 0.03, 0.03)
    vis_prim.GetAttribute("extent").Set(extent)
    col_prim.GetAttribute("extent").Set(extent)

    # Add collision API to collision geom
    UsdPhysics.CollisionAPI.Apply(col_prim)
    UsdPhysics.MeshCollisionAPI.Apply(col_prim)
    PhysxSchema.PhysxCollisionAPI.Apply(col_prim)

    # Create a attachment point link
    link = RigidPrim(
        prim_path=link_prim.GetPrimPath().__str__(),
        name=f"{self._name}:{link_name}",
    )
    link.disable_collisions()
    # TODO (eric): Should we disable gravity for this link?
    # link.disable_gravity()
    link.visible = False
    # Set a very small mass
    link.mass = 1e-6

    self._links[link_name] = link

    # Create an attachment between the root link (ClothPrim) and the newly created attachment point link (RigidPrim)
    attachment_path = self.root_link.prim.GetPath().AppendElementString("attachment")
    omni.kit.commands.execute("CreatePhysicsAttachment", target_attachment_path=attachment_path,
                              actor0_path=self.root_link.prim.GetPath(), actor1_path=link.prim.GetPath())

disable_gravity()

Disables gravity for this entity

Source code in omnigibson/prims/entity_prim.py
def disable_gravity(self) -> None:
    """
    Disables gravity for this entity
    """
    for link in self._links.values():
        link.disable_gravity()

enable_gravity()

Enables gravity for this entity

Source code in omnigibson/prims/entity_prim.py
def enable_gravity(self) -> None:
    """
    Enables gravity for this entity
    """
    for link in self._links.values():
        link.enable_gravity()

get_angular_velocity()

Gets the angular velocity of the root prim in stage.

Returns:

Name Type Description
velocity np.ndarray

angular velocity to set the rigid prim to, in the world frame. Shape (3,).

Source code in omnigibson/prims/entity_prim.py
def get_angular_velocity(self):
    """Gets the angular velocity of the root prim in stage.

    Returns:
        velocity (np.ndarray): angular velocity to set the rigid prim to, in the world frame. Shape (3,).
    """
    return self.root_link.get_angular_velocity()

get_joint_efforts(normalized=False)

Grabs this entity's joint efforts

Parameters:

Name Type Description Default
normalized bool

Whether returned values should be normalized to range [-1, 1] based on limits or not.

False

Returns:

Type Description

n-array: n-DOF length array of efforts

Source code in omnigibson/prims/entity_prim.py
def get_joint_efforts(self, normalized=False):
    """
    Grabs this entity's joint efforts

    Args:
        normalized (bool): Whether returned values should be normalized to range [-1, 1] based on limits or not.

    Returns:
        n-array: n-DOF length array of efforts
    """
    # Run sanity checks -- make sure our handle is initialized and that we are articulated
    assert self._handle is not None, "handles are not initialized yet!"
    assert self.n_joints > 0, "Tried to call method not intended for entity prim with no joints!"

    joint_efforts = self._dc.get_articulation_dof_states(self._handle, _dynamic_control.STATE_EFFORT)["effort"]

    # Possibly normalize values when returning
    return self._normalize_efforts(efforts=joint_efforts) if normalized else joint_efforts

get_joint_positions(normalized=False)

Grabs this entity's joint positions

Parameters:

Name Type Description Default
normalized bool

Whether returned values should be normalized to range [-1, 1] based on limits or not.

False

Returns:

Type Description

n-array: n-DOF length array of positions

Source code in omnigibson/prims/entity_prim.py
def get_joint_positions(self, normalized=False):
    """
    Grabs this entity's joint positions

    Args:
        normalized (bool): Whether returned values should be normalized to range [-1, 1] based on limits or not.

    Returns:
        n-array: n-DOF length array of positions
    """
    # Run sanity checks -- make sure our handle is initialized and that we are articulated
    assert self._handle is not None, "handles are not initialized yet!"
    assert self.n_joints > 0, "Tried to call method not intended for entity prim with no joints!"

    joint_positions = self._dc.get_articulation_dof_states(self._handle, _dynamic_control.STATE_POS)["pos"]

    # Possibly normalize values when returning
    return self._normalize_positions(positions=joint_positions) if normalized else joint_positions

get_joint_velocities(normalized=False)

Grabs this entity's joint velocities

Parameters:

Name Type Description Default
normalized bool

Whether returned values should be normalized to range [-1, 1] based on limits or not.

False

Returns:

Type Description

n-array: n-DOF length array of velocities

Source code in omnigibson/prims/entity_prim.py
def get_joint_velocities(self, normalized=False):
    """
    Grabs this entity's joint velocities

    Args:
        normalized (bool): Whether returned values should be normalized to range [-1, 1] based on limits or not.

    Returns:
        n-array: n-DOF length array of velocities
    """
    # Run sanity checks -- make sure our handle is initialized and that we are articulated
    assert self._handle is not None, "handles are not initialized yet!"
    assert self.n_joints > 0, "Tried to call method not intended for entity prim with no joints!"

    joint_velocities = self._dc.get_articulation_dof_states(self._handle, _dynamic_control.STATE_VEL)["vel"]

    # Possibly normalize values when returning
    return self._normalize_velocities(velocities=joint_velocities) if normalized else joint_velocities

get_linear_velocity()

Gets the linear velocity of the root prim in stage.

Returns:

Name Type Description
velocity np.ndarray

linear velocity to set the rigid prim to, in the world frame. Shape (3,).

Source code in omnigibson/prims/entity_prim.py
def get_linear_velocity(self):
    """
    Gets the linear velocity of the root prim in stage.

    Returns:
        velocity (np.ndarray): linear velocity to set the rigid prim to, in the world frame. Shape (3,).
    """
    return self.root_link.get_linear_velocity()

keep_still()

Zero out all velocities for this prim

Source code in omnigibson/prims/entity_prim.py
def keep_still(self):
    """
    Zero out all velocities for this prim
    """
    self.set_linear_velocity(velocity=np.zeros(3))
    self.set_angular_velocity(velocity=np.zeros(3))
    for joint in self._joints.values():
        joint.keep_still()
    # Make sure object is awake
    self.wake()

set_angular_velocity(velocity)

Sets the angular velocity of the root prim in stage.

Parameters:

Name Type Description Default
velocity np.ndarray

angular velocity to set the rigid prim to, in the world frame. Shape (3,).

required
Source code in omnigibson/prims/entity_prim.py
def set_angular_velocity(self, velocity):
    """
    Sets the angular velocity of the root prim in stage.

    Args:
        velocity (np.ndarray): angular velocity to set the rigid prim to, in the world frame. Shape (3,).
    """
    self.root_link.set_angular_velocity(velocity)

set_joint_efforts(efforts, indices=None, normalized=False)

Set the joint efforts (both actual value and target values) in simulation. Note: only works if the simulator is actively running!

Parameters:

Name Type Description Default
efforts np.ndarray

efforts to set. This should be n-DOF length if all joints are being set, or k-length (k < n) if specific indices are being set. In this case, the length of @efforts must be the same length as @indices!

required
indices None or k-array

If specified, should be k (k < n) length array of specific DOF efforts to set. Default is None, which assumes that all joints are being set.

None
normalized bool

Whether the inputted joint efforts should be interpreted as normalized values. Default is False

False
Source code in omnigibson/prims/entity_prim.py
def set_joint_efforts(self, efforts, indices=None, normalized=False):
    """
    Set the joint efforts (both actual value and target values) in simulation. Note: only works if the simulator
    is actively running!

    Args:
        efforts (np.ndarray): efforts to set. This should be n-DOF length if all joints are being set,
            or k-length (k < n) if specific indices are being set. In this case, the length of @efforts must
            be the same length as @indices!
        indices (None or k-array): If specified, should be k (k < n) length array of specific DOF efforts to set.
            Default is None, which assumes that all joints are being set.
        normalized (bool): Whether the inputted joint efforts should be interpreted as normalized values. Default
            is False
    """
    # Run sanity checks -- make sure our handle is initialized and that we are articulated
    assert self._handle is not None, "handles are not initialized yet!"
    assert self.n_joints > 0, "Tried to call method not intended for entity prim with no joints!"

    # Possibly de-normalize the inputs
    if normalized:
        efforts = self._denormalize_efforts(efforts=efforts, indices=indices)

    # Grab current DOF states
    dof_states = self._dc.get_articulation_dof_states(self._handle, _dynamic_control.STATE_EFFORT)

    # Possibly set specific values in the array if indies are specified
    if indices is None:
        new_efforts = efforts
    else:
        new_efforts = dof_states["effort"]
        new_efforts[indices] = efforts

    # Set the DOF states
    dof_states["effort"] = new_efforts
    self._dc.set_articulation_dof_states(self._handle, dof_states, _dynamic_control.STATE_EFFORT)

set_joint_positions(positions, indices=None, normalized=False, drive=False)

Set the joint positions (both actual value and target values) in simulation. Note: only works if the simulator is actively running!

Parameters:

Name Type Description Default
positions np.ndarray

positions to set. This should be n-DOF length if all joints are being set, or k-length (k < n) if specific indices are being set. In this case, the length of @positions must be the same length as @indices!

required
indices None or k-array

If specified, should be k (k < n) length array of specific DOF positions to set. Default is None, which assumes that all joints are being set.

None
normalized bool

Whether the inputted joint positions should be interpreted as normalized values. Default is False

False
drive bool

Whether the positions being set are values that should be driven naturally by this entity's motors or manual values to immediately set. Default is False, corresponding to an instantaneous setting of the positions

False
Source code in omnigibson/prims/entity_prim.py
def set_joint_positions(self, positions, indices=None, normalized=False, drive=False):
    """
    Set the joint positions (both actual value and target values) in simulation. Note: only works if the simulator
    is actively running!

    Args:
        positions (np.ndarray): positions to set. This should be n-DOF length if all joints are being set,
            or k-length (k < n) if specific indices are being set. In this case, the length of @positions must
            be the same length as @indices!
        indices (None or k-array): If specified, should be k (k < n) length array of specific DOF positions to set.
            Default is None, which assumes that all joints are being set.
        normalized (bool): Whether the inputted joint positions should be interpreted as normalized values. Default
            is False
        drive (bool): Whether the positions being set are values that should be driven naturally by this entity's
            motors or manual values to immediately set. Default is False, corresponding to an instantaneous
            setting of the positions
    """
    # Run sanity checks -- make sure our handle is initialized and that we are articulated
    assert self._handle is not None, "handles are not initialized yet!"
    assert self.n_joints > 0, "Tried to call method not intended for entity prim with no joints!"

    # Possibly de-normalize the inputs
    if normalized:
        positions = self._denormalize_positions(positions=positions, indices=indices)

    # Grab current DOF states
    dof_states = self._dc.get_articulation_dof_states(self._handle, _dynamic_control.STATE_POS)

    # Possibly set specific values in the array if indies are specified
    if indices is None:
        assert len(positions) == self._n_dof, \
            "set_joint_positions called without specifying indices, but the desired positions do not match n_dof."
        new_positions = positions
    else:
        new_positions = dof_states["pos"]
        new_positions[indices] = positions

    # Set the DOF states
    dof_states["pos"] = new_positions
    if not drive:
        self._dc.set_articulation_dof_states(self._handle, dof_states, _dynamic_control.STATE_POS)
        BoundingBoxAPI.clear()

    # Also set the target
    self._dc.set_articulation_dof_position_targets(self._handle, new_positions.astype(np.float32))

set_joint_velocities(velocities, indices=None, normalized=False, drive=False)

Set the joint velocities (both actual value and target values) in simulation. Note: only works if the simulator is actively running!

Parameters:

Name Type Description Default
velocities np.ndarray

velocities to set. This should be n-DOF length if all joints are being set, or k-length (k < n) if specific indices are being set. In this case, the length of @velocities must be the same length as @indices!

required
indices None or k-array

If specified, should be k (k < n) length array of specific DOF velocities to set. Default is None, which assumes that all joints are being set.

None
normalized bool

Whether the inputted joint velocities should be interpreted as normalized values. Default is False

False
drive bool

Whether the velocities being set are values that should be driven naturally by this entity's motors or manual values to immediately set. Default is False, corresponding to an instantaneous setting of the velocities

False
Source code in omnigibson/prims/entity_prim.py
def set_joint_velocities(self, velocities, indices=None, normalized=False, drive=False):
    """
    Set the joint velocities (both actual value and target values) in simulation. Note: only works if the simulator
    is actively running!

    Args:
        velocities (np.ndarray): velocities to set. This should be n-DOF length if all joints are being set,
            or k-length (k < n) if specific indices are being set. In this case, the length of @velocities must
            be the same length as @indices!
        indices (None or k-array): If specified, should be k (k < n) length array of specific DOF velocities to set.
            Default is None, which assumes that all joints are being set.
        normalized (bool): Whether the inputted joint velocities should be interpreted as normalized values. Default
            is False
        drive (bool): Whether the velocities being set are values that should be driven naturally by this entity's
            motors or manual values to immediately set. Default is False, corresponding to an instantaneous
            setting of the velocities
    """
    # Run sanity checks -- make sure our handle is initialized and that we are articulated
    assert self._handle is not None, "handles are not initialized yet!"
    assert self.n_joints > 0, "Tried to call method not intended for entity prim with no joints!"

    # Possibly de-normalize the inputs
    if normalized:
        velocities = self._denormalize_velocities(velocities=velocities, indices=indices)

    # Grab current DOF states
    dof_states = self._dc.get_articulation_dof_states(self._handle, _dynamic_control.STATE_VEL)

    # Possibly set specific values in the array if indies are specified
    if indices is None:
        new_velocities = velocities
    else:
        new_velocities = dof_states["vel"]
        new_velocities[indices] = velocities

    # Set the DOF states
    dof_states["vel"] = new_velocities
    if not drive:
        self._dc.set_articulation_dof_states(self._handle, dof_states, _dynamic_control.STATE_VEL)

    # Also set the target
    self._dc.set_articulation_dof_velocity_targets(self._handle, new_velocities.astype(np.float32))

set_linear_velocity(velocity)

Sets the linear velocity of the root prim in stage.

Parameters:

Name Type Description Default
velocity np.ndarray

linear velocity to set the rigid prim to, in the world frame. Shape (3,).

required
Source code in omnigibson/prims/entity_prim.py
def set_linear_velocity(self, velocity: np.ndarray):
    """
    Sets the linear velocity of the root prim in stage.

    Args:
        velocity (np.ndarray): linear velocity to set the rigid prim to, in the world frame. Shape (3,).
    """
    self.root_link.set_linear_velocity(velocity)

sleep()

Disable physics for this articulation

Source code in omnigibson/prims/entity_prim.py
def sleep(self):
    """
    Disable physics for this articulation
    """
    if self.articulated:
        self._dc.sleep_articulation(self._handle)
    else:
        for link in self._links.values():
            link.sleep()

update_handles()

Updates all internal handles for this prim, in case they change since initialization

Source code in omnigibson/prims/entity_prim.py
def update_handles(self):
    """
    Updates all internal handles for this prim, in case they change since initialization
    """
    assert og.sim.is_playing(), "Simulator must be playing if updating handles!"

    # Grab the handle -- we know it might not return a valid value, so we suppress omni's warning here
    self._handle = None if self.articulation_root_path is None else \
        self._dc.get_articulation(self.articulation_root_path)

    # Sanity check -- make sure handle is not invalid handle -- it should only ever be None or a valid integer
    assert self._handle != _dynamic_control.INVALID_HANDLE, \
        f"Got invalid articulation handle for entity at {self.articulation_root_path}"

    # We only have a root handle if we're not a cloth prim
    if self._prim_type != PrimType.CLOTH:
        self._root_handle = self._dc.get_articulation_root_body(self._handle) if \
            self._handle is not None else self.root_link.handle

    # Update all links and joints as well
    for link in self._links.values():
        if not link.initialized:
            link.initialize()
        link.update_handles()

    for joint in self._joints.values():
        if not joint.initialized:
            joint.initialize()
        joint.update_handles()

update_joints()

Helper function to refresh owned joints. Useful for synchronizing internal data if additional bodies are added manually

Source code in omnigibson/prims/entity_prim.py
def update_joints(self):
    """
    Helper function to refresh owned joints. Useful for synchronizing internal data if
    additional bodies are added manually
    """
    # Make sure to clean up all pre-existing names for all joints
    if self._joints is not None:
        for joint in self._joints.values():
            joint.remove_names()

    # Initialize joints dictionary
    self._joints = dict()
    self.update_handles()

    # Handle case separately based on whether the handle is valid (i.e.: whether we are actually articulated or not)
    if (not self.kinematic_only) and self._handle is not None:
        root_prim = get_prim_at_path(self._dc.get_rigid_body_path(self._root_handle))
        n_dof = self._dc.get_articulation_dof_count(self._handle)

        # Additionally grab DOF info if we have non-fixed joints
        if n_dof > 0:
            self._dofs_infos = dict()
            # Grab DOF info
            for index in range(n_dof):
                dof_handle = self._dc.get_articulation_dof(self._handle, index)
                dof_name = self._dc.get_dof_name(dof_handle)
                # add dof to list
                prim_path = self._dc.get_dof_path(dof_handle)
                self._dofs_infos[dof_name] = DOFInfo(prim_path=prim_path, handle=dof_handle, prim=self.prim,
                                                     index=index)

            for i in range(self._dc.get_articulation_joint_count(self._handle)):
                joint_handle = self._dc.get_articulation_joint(self._handle, i)
                joint_name = self._dc.get_joint_name(joint_handle)
                joint_path = self._dc.get_joint_path(joint_handle)
                joint_prim = get_prim_at_path(joint_path)
                # Only add the joint if it's not fixed (i.e.: it has DOFs > 0)
                if self._dc.get_joint_dof_count(joint_handle) > 0:
                    joint = JointPrim(
                        prim_path=joint_path,
                        name=f"{self._name}:joint_{joint_name}",
                        articulation=self._handle,
                    )
                    joint.initialize()
                    self._joints[joint_name] = joint
    else:
        # TODO: May need to extend to clusters of rigid bodies, that aren't exactly joined
        # We assume this object contains a single rigid body
        body_path = f"{self._prim_path}/{self.root_link_name}"
        root_prim = get_prim_at_path(body_path)
        n_dof = 0

    # Make sure root prim stored is the same as the one found during initialization
    assert self.root_prim == root_prim, \
        f"Mismatch in root prims! Original was {self.root_prim.GetPrimPath()}, " \
        f"initialized is {root_prim.GetPrimPath()}!"

    # Store values internally
    self._n_dof = n_dof
    self._update_joint_limits()

Helper function to refresh owned joints. Useful for synchronizing internal data if additional bodies are added manually

Parameters:

Name Type Description Default
load_config None or dict

If specified, should contain keyword-mapped values that are relevant for

None
Source code in omnigibson/prims/entity_prim.py
def update_links(self, load_config=None):
    """
    Helper function to refresh owned joints. Useful for synchronizing internal data if
    additional bodies are added manually

    Args:
        load_config (None or dict): If specified, should contain keyword-mapped values that are relevant for
        loading each of the link's rigid prims
    """
    # Make sure to clean up all pre-existing names for all links
    if self._links is not None:
        for link in self._links.values():
            link.remove_names()

    # We iterate over all children of this object's prim,
    # and grab any that are presumed to be rigid bodies (i.e.: other Xforms)
    self._links = dict()
    joint_children = set()
    for prim in self._prim.GetChildren():
        link_cls = None
        link_name = prim.GetName()
        if self._prim_type == PrimType.RIGID and prim.GetPrimTypeInfo().GetTypeName() == "Xform":
            # For rigid body object, process prims that are Xforms (e.g. rigid links)
            link_cls = RigidPrim
            # Also iterate through all children to infer joints and determine the children of those joints
            # We will use this info to infer which link is the base link!
            for child_prim in prim.GetChildren():
                if "joint" in child_prim.GetPrimTypeInfo().GetTypeName().lower():
                    # Store the child target of this joint
                    relationships = {r.GetName(): r for r in child_prim.GetRelationships()}
                    # Only record if this is NOT a fixed link tying us to the world (i.e.: no target for body0)
                    if len(relationships["physics:body0"].GetTargets()) > 0:
                        joint_children.add(relationships["physics:body1"].GetTargets()[0].pathString.split("/")[-1])

        elif self._prim_type == PrimType.CLOTH and prim.GetPrimTypeInfo().GetTypeName() == "Mesh":
            # For cloth object, process prims that are Meshes
            link_cls = ClothPrim

        if link_cls is not None:
            self._links[link_name] = link_cls(
                prim_path=prim.GetPrimPath().__str__(),
                name=f"{self._name}:{link_name}",
                load_config=load_config,
            )

    # Infer the correct root link name -- this corresponds to whatever link does not have any joint existing
    # in the children joints
    valid_root_links = list(set(self._links.keys()) - joint_children)

    # TODO: Uncomment safety check here after we figure out how to handle legacy multi-bodied assets like bed with pillow
    # assert len(valid_root_links) == 1, f"Only a single root link should have been found for this entity prim, " \
    #                                    f"but found multiple instead: {valid_root_links}"
    self._root_link_name = valid_root_links[0] if len(valid_root_links) == 1 else "base_link"

wake()

Enable physics for this articulation

Source code in omnigibson/prims/entity_prim.py
def wake(self):
    """
    Enable physics for this articulation
    """
    if self.articulated:
        self._dc.wake_up_articulation(self._handle)
    else:
        for link in self._links.values():
            link.wake()