Lidar fails in omni.isaac.sim.python.gym.headless.render.kit mode

Hi,

I’m trying to use the lidar together with cameras. To speed things up I’d like to use the headless mode, for which I"m following OmniIsaacGym and set the experience as follows:

        experience = ""
        if headless:
            if enable_livestream:
                experience = ""
            elif enable_viewport:
                experience = f'{os.environ["EXP_PATH"]}/omni.isaac.sim.python.gym.headless.render.kit'
            else:
                experience = f'{os.environ["EXP_PATH"]}/omni.isaac.sim.python.gym.headless.kit'

The lidar works fine with experience = "" and experience = f'{os.environ["EXP_PATH"]}/omni.isaac.sim.python.gym.headless.kit' (as long as I add a render call, following this advice Unable to get depth data with LIDAR sensor in headless mode).

But when I try to use it together with a camera (setting experience = f'{os.environ["EXP_PATH"]}/omni.isaac.sim.python.gym.headless.render.kit'), I receive the following error:

[19.510s] [ext: omni.isaac.occupancy_map-0.2.7] startup
Task Device: cuda:0
RL device:  cuda:0
/opt/conda/envs/isaac-sim/lib/python3.7/site-packages/gym/spaces/box.py:74: UserWarning: WARN: Box bound precision lowered by casting to float32
  "Box bound precision lowered by casting to {}".format(self.dtype)
[21.196s] [ext: omni.physx.flatcache-104.2.4-5.1] startup
2023-04-03 09:47:45 [24,967ms] [Warning] [omni.client.plugin]  Tick: authentication: Could not resolve host name "isaac-dev.ov.nvidia.com"
2023-04-03 09:47:45 [24,971ms] [Warning] [omni.client.plugin]  Tick: authentication: Could not resolve host name "isaac-dev.ov.nvidia.com"
2023-04-03 09:47:45 [24,975ms] [Warning] [omni.client.plugin]  Tick: authentication: Could not resolve host name "isaac-dev.ov.nvidia.com"
2023-04-03 09:47:45 [24,980ms] [Warning] [omni.isaac.core.utils.nucleus] /persistent/app/omniverse/mountedDrives setting not found
2023-04-03 09:47:46 [26,009ms] [Error] [omni.kit.commands.command] Failed to execute a command: RangeSensorCreateLidar.
  File "/opt/conda/envs/isaac-sim/lib/python3.7/runpy.py", line 193, in _run_module_as_main
    "__main__", mod_spec)
  File "/opt/conda/envs/isaac-sim/lib/python3.7/runpy.py", line 85, in _run_code
    exec(code, run_globals)
  File "/root/.vscode-server/extensions/ms-python.python-2023.4.0/pythonFiles/lib/python/debugpy/adapter/../../debugpy/launcher/../../debugpy/__main__.py", line 39, in <module>
    cli.main()
  File "/root/.vscode-server/extensions/ms-python.python-2023.4.0/pythonFiles/lib/python/debugpy/adapter/../../debugpy/launcher/../../debugpy/../debugpy/server/cli.py", line 430, in main
    run()
  File "/root/.vscode-server/extensions/ms-python.python-2023.4.0/pythonFiles/lib/python/debugpy/adapter/../../debugpy/launcher/../../debugpy/../debugpy/server/cli.py", line 284, in run_file
    runpy.run_path(target, run_name="__main__")
  File "/root/.vscode-server/extensions/ms-python.python-2023.4.0/pythonFiles/lib/python/debugpy/_vendored/pydevd/_pydevd_bundle/pydevd_runpy.py", line 322, in run_path
    pkg_name=pkg_name, script_name=fname)
  File "/root/.vscode-server/extensions/ms-python.python-2023.4.0/pythonFiles/lib/python/debugpy/_vendored/pydevd/_pydevd_bundle/pydevd_runpy.py", line 136, in _run_module_code
    mod_name, mod_spec, pkg_name, script_name)
  File "/root/.vscode-server/extensions/ms-python.python-2023.4.0/pythonFiles/lib/python/debugpy/_vendored/pydevd/_pydevd_bundle/pydevd_runpy.py", line 124, in _run_code
    exec(code, run_globals)
  File "/workspaces/mobile-rl/run_sbl_fmm.py", line 61, in <module>
    main()
  File "/workspaces/mobile-rl/run_sbl_fmm.py", line 22, in main
    env = initialize_my_task(cfg)
  File "/workspaces/mobile-rl/mobile_rl/utils.py", line 110, in initialize_my_task
    env.set_task(task=task, sim_params=sim_config.get_physics_params(), backend="torch", init_sim=init_sim)
  File "/workspaces/OmniIsaacGymEnvs/omniisaacgymenvs/envs/vec_env_rlgames.py", line 51, in set_task
    super().set_task(task, backend, sim_params, init_sim)
  File "/isaac-sim/exts/omni.isaac.gym/omni/isaac/gym/vec_env/vec_env_base.py", line 94, in set_task
    self._world.reset()
  File "/isaac-sim/exts/omni.isaac.core/omni/isaac/core/world/world.py", line 275, in reset
    task.set_up_scene(self.scene)
  File "/workspaces/mobile-rl/mobile_rl/env/learn_base_task.py", line 74, in set_up_scene
    self.env.set_up_scene(scene)
  File "/workspaces/mobile-rl/mobile_rl/env/n2m2_task.py", line 294, in set_up_scene
    center_to_rear_lidar_x=self._task_cfg["robot"]["center_to_rear_lidar_x"])
  File "/workspaces/mobile-rl/mobile_rl/robots/pr2.py", line 159, in get_lidar_sensor
    return PR2LidarSensor(prim_path=prim_path, max_range=max_range, center_to_front_lidar_x=center_to_front_lidar_x, center_to_rear_lidar_x=center_to_rear_lidar_x)
  File "/workspaces/mobile-rl/mobile_rl/robots/pr2.py", line 95, in __init__
    super().__init__(ignore_overlapping_pts=False, *args, **kwargs)
  File "/workspaces/mobile-rl/mobile_rl/robots/lidar_sensor.py", line 22, in __init__
    self.front_lidar_path, self.rear_lidar_path = self._create_lidars(prim_path=prim_path, max_range=max_range)
  File "/workspaces/mobile-rl/mobile_rl/robots/pr2.py", line 113, in _create_lidars
    result, prim = commands.execute("RangeSensorCreateLidar", path=front_lidar_path, **lidar_kwargs)
  File "/isaac-sim/kit/extscore/omni.kit.commands/omni/kit/commands/command.py", line 459, in execute
    result = omni.kit.undo.execute(command, name, kwargs)
[...skipped...]
  File "/isaac-sim/kit/extscore/omni.kit.commands/omni/kit/undo/undo.py", line 77, in execute
    result = _execute(command, name, level, history_key)
  File "/isaac-sim/kit/extscore/omni.kit.commands/omni/kit/undo/undo.py", line 454, in _execute
    raise error
  File "/isaac-sim/kit/extscore/omni.kit.commands/omni/kit/undo/undo.py", line 415, in _execute
    result = command.do()
  File "/isaac-sim/exts/omni.isaac.range_sensor/omni/isaac/range_sensor/scripts/commands.py", line 137, in do
    carb.log.error("Could not create lidar prim")

 <class 'AttributeError'> 'builtin_function_or_method' object has no attribute 'error'
2023-04-03 09:47:46 [26,017ms] [Error] [omni.kit.commands.command] Failed to execute a command: RangeSensorCreateLidar.
  File "/opt/conda/envs/isaac-sim/lib/python3.7/runpy.py", line 193, in _run_module_as_main
    "__main__", mod_spec)
  File "/opt/conda/envs/isaac-sim/lib/python3.7/runpy.py", line 85, in _run_code
    exec(code, run_globals)
  File "/root/.vscode-server/extensions/ms-python.python-2023.4.0/pythonFiles/lib/python/debugpy/adapter/../../debugpy/launcher/../../debugpy/__main__.py", line 39, in <module>
    cli.main()
  File "/root/.vscode-server/extensions/ms-python.python-2023.4.0/pythonFiles/lib/python/debugpy/adapter/../../debugpy/launcher/../../debugpy/../debugpy/server/cli.py", line 430, in main
    run()
  File "/root/.vscode-server/extensions/ms-python.python-2023.4.0/pythonFiles/lib/python/debugpy/adapter/../../debugpy/launcher/../../debugpy/../debugpy/server/cli.py", line 284, in run_file
    runpy.run_path(target, run_name="__main__")
  File "/root/.vscode-server/extensions/ms-python.python-2023.4.0/pythonFiles/lib/python/debugpy/_vendored/pydevd/_pydevd_bundle/pydevd_runpy.py", line 322, in run_path
    pkg_name=pkg_name, script_name=fname)
  File "/root/.vscode-server/extensions/ms-python.python-2023.4.0/pythonFiles/lib/python/debugpy/_vendored/pydevd/_pydevd_bundle/pydevd_runpy.py", line 136, in _run_module_code
    mod_name, mod_spec, pkg_name, script_name)
  File "/root/.vscode-server/extensions/ms-python.python-2023.4.0/pythonFiles/lib/python/debugpy/_vendored/pydevd/_pydevd_bundle/pydevd_runpy.py", line 124, in _run_code
    exec(code, run_globals)
  File "/workspaces/mobile-rl/run_sbl_fmm.py", line 61, in <module>
    main()
  File "/workspaces/mobile-rl/run_sbl_fmm.py", line 22, in main
    env = initialize_my_task(cfg)
  File "/workspaces/mobile-rl/mobile_rl/utils.py", line 110, in initialize_my_task
    env.set_task(task=task, sim_params=sim_config.get_physics_params(), backend="torch", init_sim=init_sim)
  File "/workspaces/OmniIsaacGymEnvs/omniisaacgymenvs/envs/vec_env_rlgames.py", line 51, in set_task
    super().set_task(task, backend, sim_params, init_sim)
  File "/isaac-sim/exts/omni.isaac.gym/omni/isaac/gym/vec_env/vec_env_base.py", line 94, in set_task
    self._world.reset()
  File "/isaac-sim/exts/omni.isaac.core/omni/isaac/core/world/world.py", line 275, in reset
    task.set_up_scene(self.scene)
  File "/workspaces/mobile-rl/mobile_rl/env/learn_base_task.py", line 74, in set_up_scene
    self.env.set_up_scene(scene)
  File "/workspaces/mobile-rl/mobile_rl/env/n2m2_task.py", line 294, in set_up_scene
    center_to_rear_lidar_x=self._task_cfg["robot"]["center_to_rear_lidar_x"])
  File "/workspaces/mobile-rl/mobile_rl/robots/pr2.py", line 159, in get_lidar_sensor
    return PR2LidarSensor(prim_path=prim_path, max_range=max_range, center_to_front_lidar_x=center_to_front_lidar_x, center_to_rear_lidar_x=center_to_rear_lidar_x)
  File "/workspaces/mobile-rl/mobile_rl/robots/pr2.py", line 95, in __init__
    super().__init__(ignore_overlapping_pts=False, *args, **kwargs)
  File "/workspaces/mobile-rl/mobile_rl/robots/lidar_sensor.py", line 22, in __init__
    self.front_lidar_path, self.rear_lidar_path = self._create_lidars(prim_path=prim_path, max_range=max_range)
  File "/workspaces/mobile-rl/mobile_rl/robots/pr2.py", line 116, in _create_lidars
    result, prim = commands.execute("RangeSensorCreateLidar", path=rear_lidar_path, **lidar_kwargs_rear)
  File "/isaac-sim/kit/extscore/omni.kit.commands/omni/kit/commands/command.py", line 459, in execute
    result = omni.kit.undo.execute(command, name, kwargs)
[...skipped...]
  File "/isaac-sim/kit/extscore/omni.kit.commands/omni/kit/undo/undo.py", line 77, in execute
    result = _execute(command, name, level, history_key)
  File "/isaac-sim/kit/extscore/omni.kit.commands/omni/kit/undo/undo.py", line 454, in _execute
    raise error
  File "/isaac-sim/kit/extscore/omni.kit.commands/omni/kit/undo/undo.py", line 415, in _execute
    result = command.do()
  File "/isaac-sim/exts/omni.isaac.range_sensor/omni/isaac/range_sensor/scripts/commands.py", line 137, in do
    carb.log.error("Could not create lidar prim")

 <class 'AttributeError'> 'builtin_function_or_method' object has no attribute 'error'
2023-04-03 09:47:50 [29,271ms] [Warning] [omni.physx.plugin] PhysicsUSD: Prim at path /World/envs/env_0/rl_robot/bl_caster_l_wheel_link/collisions is using obsolete 'customGeometry' attribute. To toggle custom geometry for cylinders, use the physics settings option.
2023-04-03 09:47:50 [29,272ms] [Warning] [omni.physx.plugin] PhysicsUSD: Prim at path /World/envs/env_0/rl_robot/fl_caster_r_wheel_link/collisions is using obsolete 'customGeometry' attribute. To toggle custom geometry for cylinders, use the physics settings option.
2023-04-03 09:47:50 [29,278ms] [Warning] [omni.physx.plugin] PhysicsUSD: Prim at path /World/envs/env_0/rl_robot/fr_caster_l_wheel_link/collisions is using obsolete 'customGeometry' attribute. To toggle custom geometry for cylinders, use the physics settings option.
2023-04-03 09:47:50 [29,281ms] [Warning] [omni.physx.plugin] PhysicsUSD: Prim at path /World/envs/env_0/rl_robot/fl_caster_l_wheel_link/collisions is using obsolete 'customGeometry' attribute. To toggle custom geometry for cylinders, use the physics settings option.
2023-04-03 09:47:50 [29,286ms] [Warning] [omni.physx.plugin] PhysicsUSD: Prim at path /World/envs/env_0/rl_robot/fr_caster_r_wheel_link/collisions is using obsolete 'customGeometry' attribute. To toggle custom geometry for cylinders, use the physics settings option.
2023-04-03 09:47:50 [29,287ms] [Warning] [omni.physx.plugin] PhysicsUSD: Prim at path /World/envs/env_0/rl_robot/br_caster_r_wheel_link/collisions is using obsolete 'customGeometry' attribute. To toggle custom geometry for cylinders, use the physics settings option.
2023-04-03 09:47:50 [29,287ms] [Warning] [omni.physx.plugin] PhysicsUSD: Prim at path /World/envs/env_0/rl_robot/bl_caster_r_wheel_link/collisions is using obsolete 'customGeometry' attribute. To toggle custom geometry for cylinders, use the physics settings option.
2023-04-03 09:47:50 [29,297ms] [Warning] [omni.physx.plugin] PhysicsUSD: Prim at path /World/envs/env_0/rl_robot/br_caster_l_wheel_link/collisions is using obsolete 'customGeometry' attribute. To toggle custom geometry for cylinders, use the physics settings option.
2023-04-03 09:47:50 [29,864ms] [Error] [carb.events.python] AttributeError: 'PlayButtonGroup' object has no attribute '_play_button'

At:
  /isaac-sim/kit/exts/omni.kit.widget.toolbar/omni/kit/widget/toolbar/builtin_tools/play_button_group.py(129): _on_timeline_event
  /isaac-sim/exts/omni.isaac.core/omni/isaac/core/simulation_context/simulation_context.py(549): play
  /isaac-sim/exts/omni.isaac.core/omni/isaac/core/simulation_context/simulation_context.py(387): initialize_physics
  /isaac-sim/exts/omni.isaac.core/omni/isaac/core/simulation_context/simulation_context.py(408): reset
  /isaac-sim/exts/omni.isaac.core/omni/isaac/core/world/world.py(281): reset
  /isaac-sim/exts/omni.isaac.gym/omni/isaac/gym/vec_env/vec_env_base.py(94): set_task
  /workspaces/OmniIsaacGymEnvs/omniisaacgymenvs/envs/vec_env_rlgames.py(51): set_task
  /workspaces/mobile-rl/mobile_rl/utils.py(110): initialize_my_task
  /workspaces/mobile-rl/run_sbl_fmm.py(22): main
  /workspaces/mobile-rl/run_sbl_fmm.py(61): <module>
  /root/.vscode-server/extensions/ms-python.python-2023.4.0/pythonFiles/lib/python/debugpy/_vendored/pydevd/_pydevd_bundle/pydevd_runpy.py(124): _run_code
  /root/.vscode-server/extensions/ms-python.python-2023.4.0/pythonFiles/lib/python/debugpy/_vendored/pydevd/_pydevd_bundle/pydevd_runpy.py(136): _run_module_code
  /root/.vscode-server/extensions/ms-python.python-2023.4.0/pythonFiles/lib/python/debugpy/_vendored/pydevd/_pydevd_bundle/pydevd_runpy.py(322): run_path
  /root/.vscode-server/extensions/ms-python.python-2023.4.0/pythonFiles/lib/python/debugpy/adapter/../../debugpy/launcher/../../debugpy/../debugpy/server/cli.py(284): run_file
  /root/.vscode-server/extensions/ms-python.python-2023.4.0/pythonFiles/lib/python/debugpy/adapter/../../debugpy/launcher/../../debugpy/../debugpy/server/cli.py(430): main
  /root/.vscode-server/extensions/ms-python.python-2023.4.0/pythonFiles/lib/python/debugpy/adapter/../../debugpy/launcher/../../debugpy/__main__.py(39): <module>
  /opt/conda/envs/isaac-sim/lib/python3.7/runpy.py(85): _run_code
  /opt/conda/envs/isaac-sim/lib/python3.7/runpy.py(193): _run_module_as_main

I’m running this in the latest docker container, 2022.2.1.

Alternatively, I’ve also tried to use the rtx_lidar, but could not find any examples on how to get back the pointcloud without having to use the ros bridge.

Thanks a lot for your help.

Hi @daniel.honerkamp - someone from our team will review and provide answer to your question.

Thanks a lot. As a small update, I now found that training the agent with experience = f'{os.environ["EXP_PATH"]}/omni.isaac.sim.python.gym.headless.kit' also does not produce the desired result. The simulator does not complain, but the lidar observations look very different than to experience = "". I’m not sure if they hit to obstacles (which are added as FixedCuboids then put into a RigidPrimView). Only with experience = "" the agent seems to actually observe the obstacles.

Hi @daniel.honerkamp - Apologies for delay in the response. Please try our latest Isaac Sim release and let us know if you are still having any issues.

Hi,

I have now switched to isaac sim version 4.1.0 and isaac lab.

I’m afraid with this version, it is still not possible to use the lidar, irrespective of whether I set enable_cameras=True or False.

from omni.isaac.lab.app import AppLauncher

# launch omniverse app
app_launcher = AppLauncher()
app_launcher = AppLauncher(enable_cameras = True)
simulation_app = app_launcher.app

Here how I use the lidar:

from __future__ import annotations

from dataclasses import MISSING, dataclass
import re
import numpy as np
import torch

from omni.kit import commands

import omni.isaac.lab.sim as sim_utils
from omni.isaac.lab.utils import configclass
from omni.isaac.lab.sensors.sensor_base_cfg import SensorBaseCfg
from omni.isaac.lab.sensors.sensor_base import SensorBase
from omni.isaac.lab.sim.utils import clone
from omni.isaac.lab.sim.spawners.spawner_cfg import SpawnerCfg
from omni.isaac.range_sensor._range_sensor import acquire_lidar_sensor_interface


@clone
def spawn_lidar(prim_path: str, cfg: LidarCfg):
    non_usd_cfg_param_names = ["func", "copy_from_source", "visible", "semantic_tags"]
    lidar_kwargs = {k: v for k, v in cfg.__dict__.items() if k not in non_usd_cfg_param_names}
    
    result, prim = commands.execute("RangeSensorCreateLidar", 
                                    path=prim_path, 
                                    **lidar_kwargs)
    # assert result, f"Failed to create lidar sensor at {prim_path}."
    return prim


@configclass
class LidarSpawnerCfg(SpawnerCfg):
    func = spawn_lidar
    parent: str | None = None
    min_range: float = 0.0
    max_range: float = MISSING
    horizontal_fov: int = MISSING
    vertical_fov: int = 0
    horizontal_resolution: float = 1.0
    vertical_resolution: float = 1.0
    rotation_rate: int = 0
    high_lod: bool = False
    yaw_offset: float = 0.0
    enable_semantics: bool = False
    draw_points: bool = False
    draw_lines: bool = False


@dataclass
class LidarData:
    pointcloud: np.ndarray = None


class Lidar(SensorBase):
    def __init__(self, cfg: LidarCfg):
        sensor_path = cfg.prim_path.split("/")[-1]
        sensor_path_is_regex = re.match(r"^[a-zA-Z0-9/_]+$", sensor_path) is None
        if sensor_path_is_regex:
            raise RuntimeError(
                f"Invalid prim path for the lidar sensor: {self.cfg.prim_path}."
                "\n\tHint: Please ensure that the prim path does not contain any regex patterns in the leaf."
            )        
        super().__init__(cfg)

        # spawn the asset
        if self.cfg.spawn is not None:
            self.cfg.spawn.func(self.cfg.prim_path, self.cfg.spawn)
        # check that spawn was successful
        matching_prims = sim_utils.find_matching_prims(self.cfg.prim_path)
        if len(matching_prims) == 0:
            raise RuntimeError(f"Could not find prim with path {self.cfg.prim_path}.")

        self._lidar_interface = acquire_lidar_sensor_interface()  
        self._data = LidarData()

    def __str__(self) -> str:
        """Returns: A string containing information about the instance."""
        # message for class
        return (
            f"Lidar @ '{self.cfg.prim_path}': \n"
        )

    @property
    def data(self) -> LidarData:
        # update sensors if needed
        self._update_outdated_buffers()
        # return the data
        return self._data

    def _initialize_impl(self):
        super()._initialize_impl()
        self._create_buffers()

    def _create_buffers(self):
        self._data.pointcloud = np.zeros((self._num_envs, 
                                          self.cfg.spawn.horizontal_fov, 
                                          max(self.cfg.spawn.vertical_fov, 1), 
                                          3))
        # self._data.pos_w = torch.zeros((self._view.count, 3), device=self._device)

    def _update_buffers_impl(self, env_ids: Sequence[int]):
        for env_id in env_ids:
            lidar_path = self.cfg.prim_path.replace("env_.*", f"env_{env_id}")
            pc = self._lidar_interface.get_point_cloud_data(lidar_path)
            self._data.pointcloud[env_id] = pc


@configclass
class LidarCfg(SensorBaseCfg):
    class_type: type = Lidar
    spawn: LidarSpawnerCfg = MISSING
    center_to_lidar_x_offset: float = MISSING

Secondly, I currently have to loop over all cloned prims and get the pointclouds individually for each environment. is there a more efficient way to get the pointclouds of all environments?

        for env_id in env_ids:
            lidar_path = self.cfg.prim_path.replace("env_.*", f"env_{env_id}")
            pc = self._lidar_interface.get_point_cloud_data(lidar_path)
            self._data.pointcloud[env_id] = pc

Thanks a lot for your help. Solutions to these problems would help me a lot to use isaac sim efficiently