Ray Caster

Ray Caster#

A diagram outlining the basic geometry of frame transformations

The Ray Caster sensor (and the ray caster camera) are similar to RTX based rendering in that they both involve casting rays. The difference here is that the rays cast by the Ray Caster sensor return strictly collision information along the cast, and the direction of each individual ray can be specified. They do not bounce, nor are they affected by things like materials or opacity. For each ray specified by the sensor, a line is traced along the path of the ray and the location of first collision with the specified mesh is returned. This is the method used by some of our quadruped examples to measure the local height field.

To keep the sensor performant when there are many cloned environments, the line tracing is done directly in Warp. This is the reason why specific meshes need to be identified to cast against: that mesh data is loaded onto the device by warp when the sensor is initialized. As a consequence, the current iteration of this sensor only works for literally static meshes (meshes that are not changed from the defaults specified in their USD file). This constraint will be removed in future releases.

Using a ray caster sensor requires a pattern and a parent xform to be attached to. The pattern defines how the rays are cast, while the prim properties defines the orientation and position of the sensor (additional offsets can be specified for more exact placement). Isaac Lab supports a number of ray casting pattern configurations, including a generic LIDAR and grid pattern.

@configclass
class RaycasterSensorSceneCfg(InteractiveSceneCfg):
    """Design the scene with sensors on the robot."""

    # ground plane with texture for interesting casting results
    ground = AssetBaseCfg(
        prim_path="/World/Ground",
        spawn=sim_utils.UsdFileCfg(
            usd_path=f"{ISAAC_NUCLEUS_DIR}/Environments/Terrains/rough_plane.usd",
            scale = (1,1,1),
        )
    )

    # 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")

    ray_caster = RayCasterCfg(
        prim_path="{ENV_REGEX_NS}/Robot/base/lidar_cage",
        update_period = 1/60,
        offset=RayCasterCfg.OffsetCfg(pos=(0,0,0.5)),
        mesh_prim_paths=["/World/Ground"],
        pattern_cfg=patterns.LidarPatternCfg(
          channels = 100,
          vertical_fov_range=[-90, 90],
          horizontal_fov_range = [-90,90],
          horizontal_res=1.0),
        debug_vis=True,
    )

Notice that the units on the pattern config is in degrees! Also, we enable visualization here to explicitly show the pattern in the rendering, but this is not required and should be disabled for performance tuning.

Lidar Pattern visualized

Querying the sensor for data can be done at simulation run time like any other sensor.

def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene):
  .
  .
  .
  # Simulate physics
  while simulation_app.is_running():
    .
    .
    .
    # print information from the sensors
      print("-------------------------------")
      print(scene["ray_caster"])
      print("Ray cast hit results: ", scene["ray_caster"].data.ray_hits_w)
-------------------------------
Ray-caster @ '/World/envs/env_.*/Robot/base/lidar_cage':
        view type            : <class 'omni.isaac.core.prims.xform_prim_view.XFormPrimView'>
        update period (s)    : 0.016666666666666666
        number of meshes     : 1
        number of sensors    : 1
        number of rays/sensor: 18000
        total number of rays : 18000
Ray cast hit results:  tensor([[[-0.3698,  0.0357,  0.0000],
        [-0.3698,  0.0357,  0.0000],
        [-0.3698,  0.0357,  0.0000],
        ...,
        [    inf,     inf,     inf],
        [    inf,     inf,     inf],
        [    inf,     inf,     inf]]], device='cuda:0')
-------------------------------

Here we can see the data returned by the sensor itself. Notice first that there are 3 closed brackets at the beginning and the end: this is because the data returned is batched by the number of sensors. The ray cast pattern itself has also been flattened, and so the dimensions of the array are [N, B, 3] where N is the number of sensors, B is the number of cast rays in the pattern, and 3 is the dimension of the casting space. Finally, notice that the first several values in this casting pattern are the same: this is because the lidar pattern is spherical and we have specified our FOV to be hemispherical, which includes the poles. In this configuration, the “flattening pattern” becomes apparent: the first 180 entries will be the same because it’s the bottom pole of this hemisphere, and there will be 180 of them because our horizontal FOV is 180 degrees with a resolution of 1 degree.

You can use this script to experiment with pattern configurations and build an intuition about how the data is stored by altering the triggered variable on line 99.

Code for raycaster_sensor.py
  1# Copyright (c) 2022-2024, The Isaac Lab Project Developers.
  2# All rights reserved.
  3#
  4# SPDX-License-Identifier: BSD-3-Clause
  5
  6import argparse
  7import numpy as np
  8
  9from omni.isaac.lab.app import AppLauncher
 10
 11# add argparse arguments
 12parser = argparse.ArgumentParser(description="Tutorial on adding sensors on a robot.")
 13parser.add_argument("--num_envs", type=int, default=1, help="Number of environments to spawn.")
 14# append AppLauncher cli args
 15AppLauncher.add_app_launcher_args(parser)
 16# parse the arguments
 17args_cli = parser.parse_args()
 18
 19# launch omniverse app
 20app_launcher = AppLauncher(args_cli)
 21simulation_app = app_launcher.app
 22
 23"""Rest everything follows."""
 24
 25import torch
 26
 27import omni.isaac.lab.sim as sim_utils
 28from omni.isaac.lab.assets import AssetBaseCfg
 29from omni.isaac.lab.scene import InteractiveScene, InteractiveSceneCfg
 30from omni.isaac.lab.sensors.ray_caster import RayCasterCfg, patterns
 31from omni.isaac.lab.utils import configclass
 32from omni.isaac.lab.utils.assets import ISAAC_NUCLEUS_DIR
 33
 34##
 35# Pre-defined configs
 36##
 37from omni.isaac.lab_assets.anymal import ANYMAL_C_CFG  # isort: skip
 38
 39
 40@configclass
 41class RaycasterSensorSceneCfg(InteractiveSceneCfg):
 42    """Design the scene with sensors on the robot."""
 43
 44    # ground plane
 45    ground = AssetBaseCfg(
 46        prim_path="/World/Ground",
 47        spawn=sim_utils.UsdFileCfg(
 48            usd_path=f"{ISAAC_NUCLEUS_DIR}/Environments/Terrains/rough_plane.usd",
 49            scale=(1, 1, 1),
 50        ),
 51    )
 52
 53    # lights
 54    dome_light = AssetBaseCfg(
 55        prim_path="/World/Light", spawn=sim_utils.DomeLightCfg(intensity=3000.0, color=(0.75, 0.75, 0.75))
 56    )
 57
 58    # robot
 59    robot = ANYMAL_C_CFG.replace(prim_path="{ENV_REGEX_NS}/Robot")
 60
 61    ray_caster = RayCasterCfg(
 62        prim_path="{ENV_REGEX_NS}/Robot/base/lidar_cage",
 63        update_period=1 / 60,
 64        offset=RayCasterCfg.OffsetCfg(pos=(0, 0, 0.5)),
 65        mesh_prim_paths=["/World/Ground"],
 66        pattern_cfg=patterns.LidarPatternCfg(
 67            channels=100, vertical_fov_range=[-90, 90], horizontal_fov_range=[-90, 90], horizontal_res=1.0
 68        ),
 69        debug_vis=not args_cli.headless,
 70    )
 71
 72
 73def run_simulator(sim: sim_utils.SimulationContext, scene: InteractiveScene):
 74    """Run the simulator."""
 75    # Define simulation stepping
 76    sim_dt = sim.get_physics_dt()
 77    sim_time = 0.0
 78    count = 0
 79
 80    triggered = True
 81    countdown = 42
 82
 83    # Simulate physics
 84    while simulation_app.is_running():
 85
 86        if count % 500 == 0:
 87            # reset counter
 88            count = 0
 89            # reset the scene entities
 90            # root state
 91            # we offset the root state by the origin since the states are written in simulation world frame
 92            # if this is not done, then the robots will be spawned at the (0, 0, 0) of the simulation world
 93            root_state = scene["robot"].data.default_root_state.clone()
 94            root_state[:, :3] += scene.env_origins
 95            scene["robot"].write_root_state_to_sim(root_state)
 96            # set joint positions with some noise
 97            joint_pos, joint_vel = (
 98                scene["robot"].data.default_joint_pos.clone(),
 99                scene["robot"].data.default_joint_vel.clone(),
100            )
101            joint_pos += torch.rand_like(joint_pos) * 0.1
102            scene["robot"].write_joint_state_to_sim(joint_pos, joint_vel)
103            # clear internal buffers
104            scene.reset()
105            print("[INFO]: Resetting robot state...")
106        # Apply default actions to the robot
107        # -- generate actions/commands
108        targets = scene["robot"].data.default_joint_pos
109        # -- apply action to the robot
110        scene["robot"].set_joint_position_target(targets)
111        # -- write data to sim
112        scene.write_data_to_sim()
113        # perform step
114        sim.step()
115        # update sim-time
116        sim_time += sim_dt
117        count += 1
118        # update buffers
119        scene.update(sim_dt)
120
121        # print information from the sensors
122        print("-------------------------------")
123        print(scene["ray_caster"])
124        print("Ray cast hit results: ", scene["ray_caster"].data.ray_hits_w)
125
126        if not triggered:
127            if countdown > 0:
128                countdown -= 1
129                continue
130            data = scene["ray_caster"].data.ray_hits_w.cpu().numpy()
131            np.save("cast_data.npy", data)
132            triggered = True
133        else:
134            continue
135
136
137def main():
138    """Main function."""
139
140    # Initialize the simulation context
141    sim_cfg = sim_utils.SimulationCfg(dt=0.005, device=args_cli.device)
142    sim = sim_utils.SimulationContext(sim_cfg)
143    # Set main camera
144    sim.set_camera_view(eye=[3.5, 3.5, 3.5], target=[0.0, 0.0, 0.0])
145    # design scene
146    scene_cfg = RaycasterSensorSceneCfg(num_envs=args_cli.num_envs, env_spacing=2.0)
147    scene = InteractiveScene(scene_cfg)
148    # Play the simulator
149    sim.reset()
150    # Now we are ready!
151    print("[INFO]: Setup complete...")
152    # Run the simulator
153    run_simulator(sim, scene)
154
155
156if __name__ == "__main__":
157    # run the main function
158    main()
159    # close sim app
160    simulation_app.close()