IMU Sensor#

The IMU sensor in NVIDIA Isaac Sim tracks the motion of the body and outputs simulated accelerometer and gyroscope readings. Like real IMU sensors, simulated IMUs gives acceleration and angular velocity measurements in local x, y, z axis with stage units.

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

IMU Sensor Properties

  1. enabled parameter determines if the sensor is running or note

  2. sensor period parameter specifies the time inbetween sensor measurement. A sensor period that’s lower than the physics delta time will always output the latest physics data. The sensor frequency cannot go beyond the physics frequency.

  3. angularVelocityFilterWidth parameter species the size of the angular velocity rolling average. Increase this parameter will result in smoother angular velocity output

  4. linearAccelerationFilterWidth parameter species the size of the linear acceleration rolling average. Increase this parameter will result in smoother linear acceleration output

  5. orientationFilterWidth parameter species the size of the orientation rolling average. Increase this parameter will result in smoother orientation output

The size of the data buffer used in interpolation is 2 times the max of the filter width or 20, whichever is greater

GUI#

Creating and Modifying the IMU#

Assuming there is a prim present in the scene to which you wish to add an IMU sensor, the following steps will let you create and modify an IMU sensor.

  1. To create a Physics Scene, go to the top Menu Bar and Click Create > Physics > Physics Scene. There should now be a PhysicsScene Prim in the Stage panel on the right.

  2. To create an IMU, first left click on the prim to attach the IMU on the stage, then go to the top Menu Bar and Click Create > Sensors > Imu Sensor.

  3. To change the position and orientation of the IMU, left click on the Imu_Sensor prim, then modify the Transform properties under the Property tab.

  4. To change other IMU properties, expand the Raw USD Properties section, and properties such as filter width, enable/disable sensor, and sensor period will be available to modify.

Add IMU with GUI

IMU Example#

To Run the IMU Example:

  1. Activate Robotics Examples tab from Windows > Examples > Robotics Examples.

  2. Click Robotics Examples > Sensors > IMU Sensor > Load Scene.

  3. You should now see a window containing each axis of the accelerometer and gyro readings being displayed.

  4. Press the Open Source Code button to view the source code. The source code illustrates how to load an Ant body into the scene and then add the sensor to it using the Python API.

  5. Press the PLAY button to begin simulating.

  6. Press SHIFT + LEFT_CLICK over the ant to drag it around and see changes in the readings.

../_images/isim_4.5_full_tut_gui_create_imu_sensor.webp

OmniGraph Workflow#

The following is a tutorial on using OmniGraph to interact with the IMU Sensor.

Scene Setup#

Begin by adding a Simple Articulation to the scene. The articulation file can be accessed via a Omniverse Nucleus Server in the content window. Connecting to this server allows allows you to access the library of NVIDIA Isaac Sim robots, sensors, and environments.

After connecting to the server,

  1. Search for simple_articulation in the Isaac Sim Asset Browser

  2. Drag simple_articulation onto the World prim in the Stage UI window on the right hand side to add an instance into the environment.

  3. To drive the revolute joint, in the Stage window, select the RevoluteJoint prim at /World/simple_articulation/Arm/RevoluteJoint, and scroll down to Drive in the Property window. Set the target velocity to 90 deg/s, and stiffness to 0.

Read IMU Sensor Action Graph set up

Now that your robot is set up, let’s add an IMU sensor to it and collect some data!

  1. In the Stage tab, navigate to the /World/simple_articulation/Arm prim and select it.

  2. Next add the sensor to the prim by Create > Sensors > Imu Sensor.

  3. The newly added IMU sensor can be viewed by hitting the + button next to the Arm prim.

Note

In general, sensors must be added to rigid body prims in order to correctly report data. The prims in this robot are already rigid bodies, so nothing must be done for this case.

OmniGraph Setup#

Now let’s set up the OmniGraph to collect readings from this sensor.

  1. Create the new action graph by navigating to Window > Graph Editors > Action Graph, and selecting New Action Graph in the new tab that opens.

  2. Now add the following nodes to the graph, and set their properties as follows:

  • On Playback Tick: Executes the graph nodes every simulation timestep.

  • Isaac Read IMU Node: Reads the IMU sensor. In the Property tab, set IMU Prim to /World/simple_articulation/Arm/Imu_Sensor, to point to the location of the IMU sensor prim. Select read gravity to read gravitational acceleration.

  • To String: Converts the IMU readings to string format.

  • Print Text: Prints the string readings to console. In the Property tab, set Log Level to Warning so that messages are visible in the terminal/console by default.

Connect the above nodes as follows to print out the IMU sensor reading:

Read Imu Action Graph set up

Now hit the Play button on the GUI. If set up correctly, the NVIDIA Isaac Sim internal Console should read out the IMU sensor’s angular velocity.

Read Imu Action Graph set up

Standalone Python#

Creating and Modifying the IMU#

There are two ways to create an IMU Sensor in Python - using a command, and using the wrapper class. This section provides snippets to be executed using standalone Python; these snippets are intended as a references, and should be modified further to suit your purposes. The following snippet adds a ground plane, cube prim, and physics scene to an NVIDIA Isaac Sim scene, which are required for the reference snippets further below to work correctly.

 1from isaacsim import SimulationApp
 2
 3simulation_app = SimulationApp({"headless": False})
 4
 5import numpy as np
 6from isaacsim.core.api.objects import DynamicCuboid
 7from isaacsim.core.api.objects.ground_plane import GroundPlane
 8from isaacsim.core.api.physics_context import PhysicsContext
 9
10PhysicsContext()
11GroundPlane(prim_path="/World/groundPlane", size=10, color=np.array([0.5, 0.5, 0.5]))
12DynamicCuboid(prim_path="/World/Cube",
13    position=np.array([-.5, -.2, 1.0]),
14    scale=np.array([.5, .5, .5]),
15    color=np.array([.2,.3,0.]))

Using Python Command#

You may add an IMU to the cube prim created above via the IsaacSensorCreateImuSensor command, as demonstrated in the following snippet. The only required argument is the parent path; the remaining arguments are optional.

 1import omni.kit.commands
 2from pxr import Gf
 3
 4success, _isaac_sensor_prim = omni.kit.commands.execute(
 5    "IsaacSensorCreateImuSensor",
 6    path="imu_sensor",
 7    parent="/World/Cube",
 8    sensor_period=1,
 9    linear_acceleration_filter_size=10,
10    angular_velocity_filter_size=10,
11    orientation_filter_size=10,
12    translation = Gf.Vec3d(0, 0, 0),
13    orientation = Gf.Quatd(1, 0, 0, 0),
14)

Using Python Wrapper#

You may add an IMU to the cube prim created above via the isaacsim.sensors.physics.IMUSensor Python wrapper class, as demonstrated in the following snippet. The benefit of using the wrapper class over the command is that it comes with additional helper functions to set the IMU sensor properties and retrieve sensor data.

 1from isaacsim.sensors.physics import IMUSensor
 2import numpy as np
 3
 4IMUSensor(
 5    prim_path="/World/Cube/Imu",
 6    name="imu",
 7    frequency=60, # or, dt=1./60
 8    translation=np.array([0, 0, 0]), # or, position=np.array([0, 0, 0]),
 9    orientation=np.array([1, 0, 0, 0]),
10    linear_acceleration_filter_size = 10,
11    angular_velocity_filter_size = 10,
12    orientation_filter_size = 10,
13)

Note

translation and position cannot both be provided as input arguments. frequency and dt also cannot both be provided as input arguments. The IMUSensor Python API documentation specifies the usage of each input argument.

To modify sensor parameters, you can use built-in class API calls such as set_frequency, set_dt, or USD attribute API calls.

Reading Sensor Output#

The sensors are created dynamically on PLAY. Moving the sensor prim while the simulation is running will invalidate the sensor. If you need to make hierarchical changes to the IMU like changing its rigid body parent, please stop the simulator, make the changes, and then restart the simulation.

There are also three methods for reading the sensor output: using get_sensor_reading() in the sensor interface, get_current_frame() in the IMU Python class, and the OmniGraph node Isaac Read IMU Node

The following snippets assume you have created a /World/Cube prim and IMU sensor prim using one of the two snippets above.

get_sensor_reading(sensor_path, interpolation_function = None, use_latest_data = False, read_gravity = True)

The get_sensor_reading function takes in three parameters: the prim_path to any IMU sensor prim, an interpolation function (optional) to use in place of the default linear interpolation function, and the useLatestValue flag (optional) for retrieving the data point from the current physics step if the sensor is running at a slower rate than physics rate The function will return an IsSensorReading object which has is_valid, time, lin_acc_x, lin_acc_y, lin_acc_z, ang_vel_x, ang_vel_y, ang_vel_z, and orientation properties.

Sample usage to get the reading from the current physics step with gravitational effects:

1from isaacsim.sensors.physics import _sensor
2
3_imu_sensor_interface = _sensor.acquire_imu_sensor_interface()
4_imu_sensor_interface.get_sensor_reading("/World/Cube/Imu", use_latest_data = True, read_gravity = True)

Sample usage with custom interpolation function without gravitational effects:

 1from isaacsim.sensors.physics import _sensor
 2from typing import List
 3
 4# Input Param: List of past IsSensorReadings, time of the expected sensor reading
 5def interpolation_function(data:List[_sensor.IsSensorReading], time:float) -> _sensor.IsSensorReading:
 6    interpolated_reading = _sensor.IsSensorReading()
 7    # do interpolation
 8    return interpolated_reading
 9
10
11_imu_sensor_interface = _sensor.acquire_imu_sensor_interface()
12_imu_sensor_interface.get_sensor_reading("/World/Cube/Imu", interpolation_function=interpolation_function, read_gravity = False)

Note

When custom interpolation used and read gravity flag is enabled, the sensor will pass raw acceleration measurements to the custom interpolation function and apply gravitational transforms after.

get_current_frame(read_gravity = True)

The get_current_frame() function is a wrapper around get_sensor_reading(path_to_current_sensor) function and a member function of the IMU class. This function returns a dictionary with lin_acc, ang_vel, orientation, time, and physics_step as keys for the Contact measurement. The get_current_frame() function uses the default parameters of get_sensor_reading, so it utilizes linear interpolation and last sensor reading at reading time.

Sample usage:

 1from isaacsim.sensors.physics import IMUSensor
 2import numpy as np
 3
 4sensor = IMUSensor(
 5    prim_path="/World/Cube/Imu",
 6    name="imu",
 7    frequency=60,
 8    translation=np.array([0, 0, 0]),
 9    orientation=np.array([1, 0, 0, 0]),
10    linear_acceleration_filter_size = 10,
11    angular_velocity_filter_size = 10,
12    orientation_filter_size = 10,
13)
14
15value = sensor.get_current_frame()
16print(value)

API Documentation#

See the API Documentation for complete usage information.