相机#
相机传感器通过使用 render_product
独特地定义,它是一个用于管理由渲染管线(图像)生成的数据的结构。Isaac Lab 提供了完全控制这些渲染如何通过相机参数(如焦距、姿态、类型等)创建的能力,以及通过使用 Annotators,您可以控制想要渲染的数据类型,允许您记录不仅仅是 RGB,还包括实例分割、物体姿态、物体 ID 等。
渲染的图像在 Isaac Lab 中是支持的数据类型中独特的,因为移动这些数据本身就需要极大的带宽。单个 800 x 600 图像,采用 32 位颜色(每个像素一个浮动点),大小接近 2 MB。如果我们以 60 fps 渲染并记录每一帧,那么该摄像头需要每秒传输 120 MB。将此值乘以环境中的摄像头数量以及仿真中的环境数量,你可以很快看到,摄像头数据的朴素向量化如何可能导致带宽问题。 NVIDIA 的 Isaac Lab 利用我们在 GPU 硬件方面的专业知识,提供了一个 API,专门解决渲染管线中这些扩展性问题。
平铺渲染#
备注
这个功能仅在 Isaac Sim 版本 4.2.0 及以后版本中可用。
分块渲染结合图像处理网络需要大量的内存资源,尤其是在更高分辨率下。我们建议在 RTX 4090 GPU 或类似设备上运行 512 台摄像头。
Tiled Rendering API 提供了一个向量化接口,用于从相机传感器收集数据。这对于强化学习环境非常有用,因为可以利用并行化来加速数据收集,从而加快训练循环。Tiled 渲染通过使用一个单一的 render_product
来处理场景中单个相机的 所有 克隆。单个图像的期望尺寸和环境的数量用于计算一个更大的 render_product
,由来自相机不同克隆的单个渲染拼接而成。当所有相机填充完它们的缓冲区后,渲染产品就被 “完成” 并可以作为一个单一的大图像进行移动,从而显著减少将数据从主机传输到设备的开销。例如,设备数据同步只使用一次调用,而不是每个相机一次调用,这也是 Tiled Rendering API 在处理视觉数据时更加高效的一个重要原因。
Isaac Lab 提供了用于 RGB、深度以及其他注释器的瓦片渲染 API,通过 TiledCamera
类。瓦片渲染 API 的配置可以通过 TiledCameraCfg
类来定义,指定诸如所有摄像机路径的正则表达式、摄像机的变换、所需的数据类型、要添加到场景中的摄像机类型以及摄像机分辨率等参数。
tiled_camera: TiledCameraCfg = TiledCameraCfg(
prim_path="/World/envs/env_.*/Camera",
offset=TiledCameraCfg.OffsetCfg(pos=(-7.0, 0.0, 3.0), rot=(0.9945, 0.0, 0.1045, 0.0), convention="world"),
data_types=["rgb"],
spawn=sim_utils.PinholeCameraCfg(
focal_length=24.0, focus_distance=400.0, horizontal_aperture=20.955, clipping_range=(0.1, 20.0)
),
width=80,
height=80,
)
要访问平铺渲染接口,可以创建一个 TiledCamera
对象并使用它从相机中获取数据。
tiled_camera = TiledCamera(cfg.tiled_camera)
data_type = "rgb"
data = tiled_camera.data.output[data_type]
返回的数据将被转换为形状 (num_cameras, height, width, num_channels),可以直接作为强化学习的观测值使用。
在进行渲染时,确保在启动环境时添加 --enable_cameras
参数。例如:
python scripts/reinforcement_learning/rl_games/train.py --task=Isaac-Cartpole-RGB-Camera-Direct-v0 --headless --enable_cameras
标注者#
两个 TiledCamera
和 Camera
类提供了从 replicator 获取各种类型标注器数据的 API。
"rgb"
: 一种 3 通道渲染的彩色图像。"rgba"
: 一个具有 alpha 通道的 4 通道渲染颜色图像。"distance_to_camera"
: 一张包含到相机光心的距离的图像。"distance_to_image_plane"
: 一张包含从相机平面沿相机 z 轴方向测量的 3D 点距离的图像。"depth"
: 与"distance_to_image_plane"
相同。"法线"
: 一张包含每个像素的局部表面法线向量的图像。"motion_vectors"
: 包含每个像素的运动矢量数据的图像。"semantic_segmentation"
: 语义分割数据。"instance_segmentation_fast"
: 实例分割数据."instance_id_segmentation_fast"
: 实例 ID 分割数据。
RGB 和 RGBA#

rgb
数据类型返回一个 3 通道的 RGB 彩色图像,类型为 torch.uint8
, 维度为 (B, H, W, 3)。
rgba
数据类型返回一个 4 通道的 RGBA 彩色图像,类型为 torch.uint8
, 维度为 (B, H, W, 4)。
将 torch.uint8
数据转换为 torch.float32
时,使用 255.0 除以缓冲区,得到一个 torch.float32
缓冲区,其中的数据范围从 0 到 1。
深度和距离#

distance_to_camera
返回一个单通道深度图像,表示到相机光学中心的距离。此注释器的维度为 (B, H, W, 1),数据类型为 torch.float32
。
distance_to_image_plane
返回一个单通道深度图像,表示 3D 点沿着相机 Z 轴到相机平面的距离。该标注器的维度为 (B, H, W, 1),类型为 torch.float32
。
depth
是 distance_to_image_plane
的别名,并将返回与 distance_to_image_plane
注释器相同的数据,维度为 (B, H, W, 1),类型为 torch.float32
。
法线#

normals
返回一张图像,包含每个像素处的局部表面法向量。该缓冲区的维度为 (B, H, W, 3),包含每个向量的 (x, y, z) 信息,数据类型为 torch.float32
。
运动向量#
motion_vectors
返回图像空间中的每个像素的运动向量,运动向量的二维数组表示像素在相机视口中在帧与帧之间的相对运动。缓冲区的维度为 (B, H, W, 2),其中 x 代表水平方向上的运动距离(图像宽度),向左移动时为正,向右移动时为负;y 代表垂直方向上的运动距离(图像高度),向上移动时为正,向下移动时为负。数据类型是 torch.float32
。
语义分割#

semantic_segmentation
输出相机视口中具有语义标签的每个实体的语义分割。除了图像缓冲区外,还可以通过 tiled_camera.data.info['semantic_segmentation']
获取一个 info
字典,其中包含 ID 到标签的信息。
如果
colorize_semantic_segmentation=True
在相机配置中,返回的将是一个具有维度 (B, H, W, 4) 和类型torch.uint8
的 4 通道 RGBA 图像。信息idToLabels
字典将是从颜色到语义标签的映射。如果
colorize_semantic_segmentation=False
, 则会返回一个维度为 (B, H, W, 1) 且类型为torch.int32
的缓冲区,包含每个像素的语义 ID。信息idToLabels
字典将是从语义 ID 到语义标签的映射。
实例 ID 分割#

instance_id_segmentation_fast
输出相机视口中每个实体的实例 ID 分割。每个场景中的 prim 都有唯一的实例 ID,路径不同。除了图像缓冲区,还可以通过 tiled_camera.data.info['instance_id_segmentation_fast']
获取一个 info
字典,包含 ID 到标签的信息。
instance_id_segmentation_fast
和 instance_segmentation_fast
之间的主要区别在于,实例分割注释器会一直向下层级遍历到具有语义标签的最低级别原语,而实例 ID 分割则始终向下遍历到叶子原语。
如果
colorize_instance_id_segmentation=True
在相机配置中,将返回一个4通道的RGBA图像,尺寸为(B, H, W, 4),类型为torch.uint8
。信息idToLabels
字典将是从颜色到该实体的USD prim路径的映射。如果
colorize_instance_id_segmentation=False
, 则返回一个维度为 (B, H, W, 1) 且类型为torch.int32
的缓冲区,其中包含每个像素的实例 ID。信息idToLabels
字典将是实例 ID 到该实体的 USD prim 路径的映射。
实例分割#

instance_segmentation_fast
输出摄像机视口中每个实体的实例分割。除了图像缓冲区,还可以通过 tiled_camera.data.info['instance_segmentation_fast']
获取 info
字典,其中包含 ID 到标签和 ID 到语义信息。
如果
colorize_instance_segmentation=True
在相机配置中,将返回一个具有维度 (B, H, W, 4) 和类型torch.uint8
的 4 通道 RGBA 图像。如果
colorize_instance_segmentation=False
, 将返回一个维度为 (B, H, W, 1) 且类型为torch.int32
的缓冲区,其中包含每个像素的实例 ID。
信息 idToLabels
字典将是从颜色到该语义实体的 USD prim 路径的映射。信息 idToSemantics
字典将是从颜色到该语义实体的语义标签的映射。
当前限制#
出于性能考虑,我们默认使用 DLSS 进行去噪处理,这通常能提供更好的性能。这可能导致渲染质量较低,尤其是在低分辨率下尤为明显。因此,我们建议使用每瓦片或每相机分辨率至少为 100 x 100。对于低分辨率的渲染,我们建议在 RenderCfg
中设置 antialiasing_mode
属性为 DLAA
, 并且可能需要启用 enable_dl_denoiser
。这两个设置应该有助于提高渲染质量,但也会带来性能的损耗。还可以在 RenderCfg
中指定其他渲染参数。