Rigging a Robot

With the exception of using URDF importer, most robots imported using CAD or other 3DCG software may not contain joint information. This is a step-by-step instruction on how to rig a robot, and turn static parts into an articulated, controllable robot.

From CAD Imports

Prepare CAD Assemblies

Exporting your assembly in a default position where parts are aligned at the joints, and assmebly are symmetrical and aligned with a reference frame will make the rigging much easier.

Label Rigid Body Parts

Articulation can only be calculated on rigid bodies, so the first step is to make the relevant parts of the robot rigid bodies. Not every single piece of the assembly needs to be a rigid body, skipping parts such as bolts and nuts can significantly lighten the physics simulation load.

Select the Xform corresponding to the part, and under PhysX Properties tab, go to Add Prim Component and click on PhysicsAPI. Repeat for each part.

../_images/isaac_robot_add_rigid_body.png

Add Joints

  1. Select parts. Ctrl-Shift and click to multi-select the Xforms that will be connected by the joint. The first one you select is the child (body1), the second one is the parent (body0).

  2. Select joint type. Physics -> Joint Attributes-> Type -> Revolute/Prismatic/etc.

  3. Add joint. Physics -> Add -> Joint -> Between Selected. A joint will now appear under the parent Xform. You can move it out of the parent’s branch if desired. You can always find the relevant information regarding the joint under PhysX Properties -> Physics Joint.

  1. Place the joint. The joint is by default placed at the origin of the parent part. In most cases, this is not where the joint is. We will manually type in the joint location in reference to one of the rigid bodies involved. You may use body0 as the reference, or body1.

    1. In the video above, you will see that the joint is placed by offsetting it from the parent body (localPos0) in the y and z directions.

    2. In the video below, you can see that the same joint can be placed by using the child as the reference frame. First you can find the center of the child’s rigid body by making localPos1 to be zeros, and localRot1 to be all zeros except for one of the terms, which should be 1. Then you can type in the joint offset from the origin from there.

    3. You can also directly drag the joint using the gizmo in the viewport, although that will likely to be very inaccurate.

Note

The origin of each mesh is automatically placed at the center of mass (COM) when imported using the STEP importer. For asymmetrical parts, this will not be the center of the part. Make sure the joint position offset is the offset from the COM, and not the origin of the part in your CAD or mesh file.

Add Articulations

Articulations are an advanced, hierarchic mode of joints, optimized for mechanism and the objects that are connect in a tree structure. It is faster and more stable to calculate the joints on a robot when they are turned into a chain of articulations.

To turn the joints into articulations:

  1. Add ArticulationAPI to the main robot Prim. Select the main robot Prim on the Stage Tree, and go to PhysX Properties->Add Prim Component and select ArticulationAPI. If your robot is suppose to be stationary, check the fixBase box.

  2. Establish the root of the articulation, or the start of the kinematic chain, such as the base of a manipulator, or the chassis of a vehicle. Find the Prim that represents this root link on the Stage Tree, then go to the menu Physics -> Add -> Joint -> To World Space. A joint will appear under the root Prim. You can rename it and even move it out of the root Prim and into the main robot Prim.

  3. Remove the default joint type that was added to the root joint by going to PhysX Properties-> Remove Prim Component and select whatever joint type that appears under the dropdown menu. By selecting it, it is removed. You can check by opening the dropdown menu again, and it should be empty.

  4. Add the ArticulationJoint to this root joint instead. Go to PhysX Properties->Add Joint Component, select ArticulationJoint. This enables the section under the PhysX Proerties called Physics Articulation Joint. Select ArticulatedRootFixedBase for the dropdown menu “Articulation Joint Type”. If your robot is mobile and does not have a fixed base, select ArticulatedRoot instead.

  5. For rest of the joints in the kinematic chain. Select the joint on the stage tree, and go togo to PhysX Properties->Add Joint Component and select ArticulationJoint

Robots with Closed Kinematic Chains

Currently, articulation features are only supporting tree-like kinematic chains, and will not work for closed-kinematic chains. Therefore, if your robot has a closed-kinematic chain, you will need to break it up by skipping one of the joints when defining the articulation chain. In this simple platform example, all the spherical joint connecting the legs to the top plate are not included in the articulation chain.

Add Collision

To add collision properties to a rigid body, select the Mesh that is associated with the body on the Stage Tree (as oppose to the Xform). Then go to PhysX Properties->Add Prim Component and add CollisionAPI.

../_images/isaac_robot_add_collision.png

Visualize Collision Meshes

Not all the rigid bodies need to have collision properties, and collision meshes are often a simplified mesh comparing to the visual ones. Therefore you may want to visualize the collision mesh for inspection. Go to Physics->PhysX Debug Window, Under Physics debug visualization category, open up the dropdown list for Show collision shapes, and select All. The collision meshes will now be outlined in purple.

You can also achieve the same result by clicking on the eye icon in the upper left corner of the Viewport, and go to Show By Type -> Physics Mesh and select All.

The visualization of collision meshes uses the PhysX Visual Debugger (PVD) plugin. You can find more information on PVD itself here.

Add Joint Drives

For joints that are actuated, we need to add joint drive properties to it. Select the desired joint on the Stage Tree, and go to PhysX Properties->Add Joint Component and add Drive. This enables the section “Joint Drive” under the “PhysX Properties” tab.

Currently, two types of drives are supported: position and velocity. For position drive, set a relative high stiffness comparing to the damping, and set a reasonable maxForce. For velocity drive, set only damping and set stiffness to 0.

You can test if the drive is active by start the simulation and manually change the drive target.

Joint Limits

You can add joint limits to each joint by going to PhysX Properties->Add Joint Component and add Limit. A new section called “Joint Limit” will appear under the PhysX Properties tab.

../_images/isaac_robot_joint-limit.png

Rigging a Mobile Robot

The steps for rigging a mobile robot is very similar. The biggest difference being the robot’s base is not fixed. Here is a step-by-step tutorial in video.

Extending a Robot

If you have an existing rigged robot, it is possible to create alternate versions of the robot using the same base asset. For example, the UR10 base asset was loaded from the example ur10 urdf, which contains no end effector. And then two derived versions are shown, with a short surface gripper, and a longer surface gripper. Changes made in the base assets this way will impact all assets which contain it as reference.

Example

These are the steps to create an extended robot model:

  1. Create a new empty scenario. If any world prim is created, delete it.

  2. Locate the base robot in the contents path, and drag it onto the scene. at the position (0,0,0). In the video example we are using the UR10 robot.

  3. Set the Robot root as the default Prim by Right-clicking at the robot root and selecting Set Default Prim.

  4. Create an XForm inside the end robot’s effector link and set its pose to (0,0,0). In the example we will place it under wrist_3_link, and name the new Xform ee_link.

  5. Move the XForm outside of the end effector link and inside the robot link.

  6. Make the new XForm instanceable.

  7. Under the PhysX Properties tab, Add the Physics API Prim component.

  8. Locate the End Effector Asset and drag it into the newly created Xform.

  9. In the Physics menu, select Physics->Joint Atrributes->Fixed.

  10. Select the robot link, and the newly created Xform, and on the Physixs menu select Physics->Add->Joint->Between Selected. This will create a fixed joint between the new robot’s end effctor link and the newly created link.

  11. Make any final changes to the asset, and save the file.

Python API

Here are some useful Python API snippets that will get you started with loading your robot into Omniverse Isaac Sim and configuring it. Versions of the code below can be found in the samples’ scripts. This can also run directly inside Kit’s Script Editor.