API#

Python API#

Generator

This class is used to generate an occupancy map for a USD stage.


class Generator#

Bases: pybind11_object

This class is used to generate an occupancy map for a USD stage. Assuming the stage has collision geometry information, the following code can be used to generate the occupancy map information

Example

import omni
from isaacsim.asset.gen.omap import _omap

physx = omni.physx.acquire_physx_interface()
stage_id = omni.usd.get_context().get_stage_id()

generator = _omap.Generator(physx, stage_id)
# 0.05m cell size, output buffer will have 4 for occupied cells, 5 for unoccupied, and 6 for cells that cannot be seen
# this assumes your usd stage units are in m, and not cm
generator.update_settings(.05, 4, 5, 6)
# Set location to map from and the min and max bounds to map to
generator.set_transform((0, 0, 0), (-2, -2, 0), (2, 2, 0))
generator.generate2d()
# Get locations of the occupied cells in the stage
points = generator.get_occupied_positions()
# Get computed 2d occupancy buffer
buffer = generator.get_buffer()
# Get dimensions for 2d buffer
dims = generator.get_dimensions()
__init__(
self: isaacsim.asset.gen.omap.bindings._omap.Generator,
arg0: omni::physx::IPhysx,
arg1: int,
) None#
Parameters:
  • interface (arg0 Pointer to PhysX)

  • map (arg1 Stage ID for the USD stage to)

generate2d(
self: isaacsim.asset.gen.omap.bindings._omap.Generator,
) None#

Main function that generates a map based on the settings and transform set. Assumes that a 2d map is generated and flattens the computed data

generate3d(
self: isaacsim.asset.gen.omap.bindings._omap.Generator,
) None#

Main function that generates a map based on the settings and transform set. Assumes 3d generation, map is not flattened

get_buffer(
self: isaacsim.asset.gen.omap.bindings._omap.Generator,
) List[float]#
Returns:

2D array containing values for each cell in the occupancy map.

Return type:

list of float

get_colored_byte_buffer(
self: isaacsim.asset.gen.omap.bindings._omap.Generator,
arg0: carb::Int4,
arg1: carb::Int4,
arg2: carb::Int4,
) List[str]#

Convenience function to generate an image from the occupancy map

Parameters:
  • arg0 (carb.Int4) – RGBA Value used to denote an occupied cell

  • arg1 (carb.Int4) – RGBA Value used to denote an unoccupied cell

  • arg2 (carb.Int4) – RGBA Value used to denote unknown areas that could not be reached from the starting location

Returns:

Flattened buffer containing list of RGBA values for each pixel. Can be used to render as image directly

Return type:

list of int

get_dimensions(
self: isaacsim.asset.gen.omap.bindings._omap.Generator,
) carb::Int3#
Returns:

Dimensions for output buffer

Return type:

carb.Int3

get_free_positions(
self: isaacsim.asset.gen.omap.bindings._omap.Generator,
) List[carb::Float3]#
Returns:

List of 3d points in stage coordinates from the generated map, containing free locations.

Return type:

list of carb.Float3

get_max_bound(
self: isaacsim.asset.gen.omap.bindings._omap.Generator,
) carb::Float3#
Returns:

Maximum bound for generated occupancy map instage coordinates

Return type:

carb.Float3

get_min_bound(
self: isaacsim.asset.gen.omap.bindings._omap.Generator,
) carb::Float3#
Returns:

Minimum bound for generated occupancy map instage coordinates

Return type:

carb.Float3

get_occupied_positions(
self: isaacsim.asset.gen.omap.bindings._omap.Generator,
) List[carb::Float3]#
Returns:

List of 3d points in stage coordinates from the generated map, containing occupied locations.

Return type:

list of carb.Float3

set_transform(
self: isaacsim.asset.gen.omap.bindings._omap.Generator,
arg0: carb::Float3,
arg1: carb::Float3,
arg2: carb::Float3,
) None#

Set origin and bounds for mapping

Parameters:
  • arg0 (carb.Float3) – Origin in stage to start mapping from, must be in unoccupied space

  • arg1 (carb.Float3) – Minimum bound to map up to

  • arg2 (carb.Float3) – Maximum bound to map up to

update_settings(
self: isaacsim.asset.gen.omap.bindings._omap.Generator,
arg0: float,
arg1: float,
arg2: float,
arg3: float,
) None#

Updates settings used for generating the occupancy map

Parameters:
  • arg0 (float) – Size of the cell in stage units, resolution of the grid

  • arg1 (float) – Value used to denote an occupied cell

  • arg2 (float) – Value used to denote an unoccupied cell

  • arg3 (float) – Value used to denote unknown areas that could not be reached from the starting location