Force Sensor

Force Sensors can be created for Rigid Bodies within Articulations and readings can be retrieved through the ArticulationView as a buffer of tensors for sensors within the ArticulationView.

See the Isaac Sim Conventions documentation for a complete list of Omniverse Isaac Sim conventions.

Warning

The get_force_sensor_forces() API described in this page is recently deprecated and will no longer be supported.

Isaac Example

Sensors can be added from the UI by right clicking on a Rigid Body inside an Articulation, then from the menu, select Add > Physics > Articulation Force Sensor.

../../_images/isaac_sim_add_force_sensor.png

To retrieve readings from the added sensors, first create an ArticulationView, then use the get_force_sensor_forces() API, which will return a buffer of dimension (num_articulations, num_sensors_per_articulation, 6).

robots = ArticulationView(prim_paths_expr="/World/envs/.*/Ant/torso")

# start simulation
...

sensor_readings = robots._physics_view.get_force_sensor_forces()

Articulation Joint Sensors

Articulation sensors allow reading the active and passive components of the joint forces. To read articulation joint forces, first create an ArticulationView (see Isaac Core for more information about different core extension view classes and how to use their APIs).

If you want to apply efforts to the articulation DOFs, you can use set_joint_efforts() which requires a tensor of dimension (num_articulations, num_joints).

get_applied_joint_efforts() API will return a buffer of dimension (num_articulations, num_joints) that specifies the efforts set by the user through the set_joint_efforts().

get_measured_joint_forces() API will return a buffer of dimension (num_articulations, num_links, 6) that specifies a 6-dimensional force/torque per joints for all articulations. To mimic force-torque sensors, this API can be used to retrieve forces from a fixed joint.

On the other hand, get_measured_joint_efforts() API will return a buffer of dimension (num_articulations, num_links) which specifies the active component (the projection of the joint forces on the motion direction) of the joint force for all the joints and articulations.

robots = ArticulationView(prim_paths_expr="/World/envs/.*/Ant/torso")

# start simulation
...

# define the actuation_tensor and apply joint efforts directly to the articulation DOFS via
robots.set_joint_efforts(actuation_tensor)
...

# read the applied joint efforts afer all the set operations
applied_joint_efforts = robots.get_applied_joint_efforts()
...

# read total overall joint forces and torques via
sensor_joint_forces = robots.get_measured_joint_forces()
...

# read the active component of the joint forces, i.e. the joint efforts via
sensor_actuation_efforts = robots.get_measured_joint_efforts()

Please note that the forces are reported for the link incoming joints of the articulations. In the articulation tree, each link can have a single parent link, and the joint forces reported through the mentioned APIs correspond to the forces, torques, or efforts exerted by the joint connecting the child link to the parent link. The following snippet illustrates how to establish a mapping between articulation joints and articulation links, and how to retrieve the respective joint forces and efforts using the aforementioned APIs for a specific joint.

from omni.isaac.core.articulations import Articulation
import asyncio
from omni.isaac.core import World
from omni.isaac.core.utils.stage import (
    add_reference_to_stage,
    create_new_stage_async,
    get_current_stage,
)
from omni.isaac.core.utils.nucleus import get_assets_root_path
from pxr import UsdPhysics

async def joint_force():
    World.clear_instance()
    await create_new_stage_async()
    my_world = World(stage_units_in_meters=1.0, backend="torch", device="cpu")
    await my_world.initialize_simulation_context_async()
    await omni.kit.app.get_app().next_update_async()
    assets_root_path = get_assets_root_path()
    asset_path = assets_root_path + "/Isaac/Robots/Ant/ant.usd"
    add_reference_to_stage(usd_path=asset_path, prim_path="/World/Ant")
    await omni.kit.app.get_app().next_update_async()
    my_world.scene.add_default_ground_plane()
    arti_view = Articulation("/World/Ant/torso")
    my_world.scene.add(arti_view)
    await my_world.reset_async(soft=False)
    stage = get_current_stage()

    sensor_joint_forces = arti_view.get_measured_joint_forces()
    sensor_actuation_efforts = arti_view.get_measured_joint_efforts()
    # Iterates through the joint names in the articulation, retrieves information about the joints and their associated links,
    # and creates a mapping between joint names and their corresponding link indices.
    joint_link_id = dict()
    for joint_name in arti_view._articulation_view.joint_names:
        joint_path = "/World/Ant/joints/" + joint_name
        joint = UsdPhysics.Joint.Get(stage, joint_path)
        body_1_path = joint.GetBody1Rel().GetTargets()[0]
        body_1_name = stage.GetPrimAtPath(body_1_path).GetName()
        child_link_index = arti_view._articulation_view.get_link_index(body_1_name)
        joint_link_id[joint_name] = child_link_index

    print("joint link IDs", joint_link_id)
    print(sensor_joint_forces[joint_link_id["front_left_leg"]])
    print(sensor_actuation_efforts[joint_link_id["front_left_leg"]])

asyncio.ensure_future(joint_force())