Inertial Measurement Unit (IMU)#
Inertial Measurement Units (IMUs) are a type of sensor for measuring the acceleration of an object. These sensors are traditionally designed report linear accelerations and angular velocities, and function on similar principles to that of a digital scale: They report accelerations derived from net force acting on the sensor.
A naive implementation of an IMU would report a negative acceleration due to gravity while the sensor is at rest in some local gravitational field. This is not generally needed for most practical applications, and so most real IMU sensors often include a gravity bias and assume that the device is operating on the surface of the Earth. The IMU we provide in Isaac Lab includes a similar bias term, which defaults to +g. This means that if you add an IMU to your simulation, and do not change this bias term, you will detect an acceleration of \(+ 9.81 m/s^{2}\) anti-parallel to gravity acceleration.
Consider a simple environment with an Anymal Quadruped equipped with an IMU on each of its two front feet.
@configclass
class ImuSensorSceneCfg(InteractiveSceneCfg):
"""Design the scene with sensors on the robot."""
# ground plane
ground = AssetBaseCfg(prim_path="/World/defaultGroundPlane", spawn=sim_utils.GroundPlaneCfg())
# lights
dome_light = AssetBaseCfg(
prim_path="/World/Light", spawn=sim_utils.DomeLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75))
)
# robot
robot = ANYMAL_C_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
imu_RF = ImuCfg(prim_path="{ENV_REGEX_NS}/Robot/LF_FOOT", debug_vis=True)
imu_LF = ImuCfg(prim_path="{ENV_REGEX_NS}/Robot/RF_FOOT", gravity_bias=(0, 0, 0), debug_vis=True)
def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene):
"""Run the simulator."""
# Define simulation stepping
sim_dt = sim.get_physics_dt()
Here we have explicitly removed the bias from one of the sensors, and we can see how this affects the reported values by visualizing the sensor when we run the sample script
Notice that the right front foot explicitly has a bias of (0,0,0). In the visualization, you should see that the arrow indicating the acceleration from the right IMU rapidly changes over time, while the arrow visualizing the left IMU points constantly along the vertical axis.
Retrieving values form the sensor is done in the usual way
def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene):
.
.
.
# Simulate physics
while simulation_app.is_running():
.
.
.
# print information from the sensors
print("-------------------------------")
print(scene["imu_LF"])
print("Received linear velocity: ", scene["imu_LF"].data.lin_vel_b)
print("Received angular velocity: ", scene["imu_LF"].data.ang_vel_b)
print("Received linear acceleration: ", scene["imu_LF"].data.lin_acc_b)
print("Received angular acceleration: ", scene["imu_LF"].data.ang_acc_b)
print("-------------------------------")
print(scene["imu_RF"])
print("Received linear velocity: ", scene["imu_RF"].data.lin_vel_b)
print("Received angular velocity: ", scene["imu_RF"].data.ang_vel_b)
print("Received linear acceleration: ", scene["imu_RF"].data.lin_acc_b)
print("Received angular acceleration: ", scene["imu_RF"].data.ang_acc_b)
The oscillations in the values reported by the sensor are a direct result of of how the sensor calculates the acceleration, which is through a finite difference approximation between adjacent ground truth velocity values as reported by the sim. We can see this in the reported result (pay attention to the linear acceleration) because the acceleration from the right foot is small, but explicitly zero.
Imu sensor @ '/World/envs/env_.*/Robot/LF_FOOT':
view type : <class 'omni.physics.tensors.impl.api.RigidBodyView'>
update period (s) : 0.0
number of sensors : 1
Received linear velocity: tensor([[ 0.0203, -0.0054, 0.0380]], device='cuda:0')
Received angular velocity: tensor([[-0.0104, -0.1189, 0.0080]], device='cuda:0')
Received linear acceleration: tensor([[ 4.8344, -0.0205, 8.5305]], device='cuda:0')
Received angular acceleration: tensor([[-0.0389, -0.0262, -0.0045]], device='cuda:0')
-------------------------------
Imu sensor @ '/World/envs/env_.*/Robot/RF_FOOT':
view type : <class 'omni.physics.tensors.impl.api.RigidBodyView'>
update period (s) : 0.0
number of sensors : 1
Received linear velocity: tensor([[0.0244, 0.0077, 0.0431]], device='cuda:0')
Received angular velocity: tensor([[ 0.0122, -0.1360, -0.0042]], device='cuda:0')
Received linear acceleration: tensor([[-0.0018, 0.0010, -0.0032]], device='cuda:0')
Received angular acceleration: tensor([[-0.0373, -0.0050, -0.0053]], device='cuda:0')
-------------------------------
Code for imu_sensor.py
1# Copyright (c) 2022-2026, The Isaac Lab Project Developers (https://github.com/isaac-sim/IsaacLab/blob/main/CONTRIBUTORS.md).
2# All rights reserved.
3#
4# SPDX-License-Identifier: BSD-3-Clause
5
6"""Launch Isaac Sim Simulator first."""
7
8import argparse
9
10from isaaclab.app import AppLauncher
11
12# add argparse arguments
13parser = argparse.ArgumentParser(description="Example on using the IMU sensor.")
14parser.add_argument("--num_envs", type=int, default=1, help="Number of environments to spawn.")
15# append AppLauncher cli args
16AppLauncher.add_app_launcher_args(parser)
17# parse the arguments
18args_cli = parser.parse_args()
19
20# launch omniverse app
21app_launcher = AppLauncher(args_cli)
22simulation_app = app_launcher.app
23
24"""Rest everything follows."""
25
26import torch
27
28import isaaclab.sim as sim_utils
29from isaaclab.assets import AssetBaseCfg
30from isaaclab.scene import InteractiveScene, InteractiveSceneCfg
31from isaaclab.sensors import ImuCfg
32from isaaclab.utils import configclass
33
34##
35# Pre-defined configs
36##
37from isaaclab_assets.robots.anymal import ANYMAL_C_CFG # isort: skip
38
39
40@configclass
41class ImuSensorSceneCfg(InteractiveSceneCfg):
42 """Design the scene with sensors on the robot."""
43
44 # ground plane
45 ground = AssetBaseCfg(prim_path="/World/defaultGroundPlane", spawn=sim_utils.GroundPlaneCfg())
46
47 # lights
48 dome_light = AssetBaseCfg(
49 prim_path="/World/Light", spawn=sim_utils.DomeLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75))
50 )
51
52 # robot
53 robot = ANYMAL_C_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
54
55 imu_RF = ImuCfg(prim_path="{ENV_REGEX_NS}/Robot/LF_FOOT", debug_vis=True)
56
57 imu_LF = ImuCfg(prim_path="{ENV_REGEX_NS}/Robot/RF_FOOT", gravity_bias=(0, 0, 0), debug_vis=True)
58
59
60def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene):
61 """Run the simulator."""
62 # Define simulation stepping
63 sim_dt = sim.get_physics_dt()
64 sim_time = 0.0
65 count = 0
66
67 # Simulate physics
68 while simulation_app.is_running():
69 if count % 500 == 0:
70 # reset counter
71 count = 0
72 # reset the scene entities
73 # root state
74 # we offset the root state by the origin since the states are written in simulation world frame
75 # if this is not done, then the robots will be spawned at the (0, 0, 0) of the simulation world
76 root_state = scene["robot"].data.default_root_state.clone()
77 root_state[:, :3] += scene.env_origins
78 scene["robot"].write_root_link_pose_to_sim(root_state[:, :7])
79 scene["robot"].write_root_com_velocity_to_sim(root_state[:, 7:])
80 # set joint positions with some noise
81 joint_pos, joint_vel = (
82 scene["robot"].data.default_joint_pos.clone(),
83 scene["robot"].data.default_joint_vel.clone(),
84 )
85 joint_pos += torch.rand_like(joint_pos) * 0.1
86 scene["robot"].write_joint_state_to_sim(joint_pos, joint_vel)
87 # clear internal buffers
88 scene.reset()
89 print("[INFO]: Resetting robot state...")
90 # Apply default actions to the robot
91 # -- generate actions/commands
92 targets = scene["robot"].data.default_joint_pos
93 # -- apply action to the robot
94 scene["robot"].set_joint_position_target(targets)
95 # -- write data to sim
96 scene.write_data_to_sim()
97 # perform step
98 sim.step()
99 # update sim-time
100 sim_time += sim_dt
101 count += 1
102 # update buffers
103 scene.update(sim_dt)
104
105 # print information from the sensors
106 print("-------------------------------")
107 print(scene["imu_LF"])
108 print("Received linear velocity: ", scene["imu_LF"].data.lin_vel_b)
109 print("Received angular velocity: ", scene["imu_LF"].data.ang_vel_b)
110 print("Received linear acceleration: ", scene["imu_LF"].data.lin_acc_b)
111 print("Received angular acceleration: ", scene["imu_LF"].data.ang_acc_b)
112 print("-------------------------------")
113 print(scene["imu_RF"])
114 print("Received linear velocity: ", scene["imu_RF"].data.lin_vel_b)
115 print("Received angular velocity: ", scene["imu_RF"].data.ang_vel_b)
116 print("Received linear acceleration: ", scene["imu_RF"].data.lin_acc_b)
117 print("Received angular acceleration: ", scene["imu_RF"].data.ang_acc_b)
118
119
120def main():
121 """Main function."""
122
123 # Initialize the simulation context
124 sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device)
125 sim = sim_utils.SimulationContext(sim_cfg)
126 # Set main camera
127 sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0])
128 # design scene
129 scene_cfg = ImuSensorSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0)
130 scene = InteractiveScene(scene_cfg)
131 # Play the simulator
132 sim.reset()
133 # Now we are ready!
134 print("[INFO]: Setup complete...")
135 # Run the simulator
136 run_simulator(sim, scene)
137
138
139if __name__ == "__main__":
140 # run the main function
141 main()
142 # close sim app
143 simulation_app.close()