NVIDIA Omniverse和Isaac Sim笔记8:相机数据采集发布帧率问题研究与设置

Feb 12,2023   6115 words   22 min

Tags: Simulation

在这篇笔记中,我们尝试回答前面一直都在说的数据采集中帧率修改的问题。在一开始,我们学习了Replicator,使用Synthetic Data Recorder进行数据采集,但问题就是帧率太低(只有个位数的帧率)。为了解决这个问题,我们进一步学习了Action Graph和Isaac Sim的ROS接口,基于此完成了对于传感器数据较高帧率的采集。但新的问题出现了,我们没有显式地设置帧率,帧率多少完全取决于硬件能力。比如这种方式直接录制的帧率可能到60FPS,但我们并不需要这么高,只要25FPS就足够了,但并不知道如何修改。在上一篇笔记中,我们尝试搭建了一个包含双目相机+IMU的小车。但类似的问题依然存在,相机和IMU的帧率相同,这显然是有问题的。所以可以看出,我们的学习进程几乎就是围绕帧率的问题展开的。不妨把相关的问题再整理一下:

  • (1) 能否手动设置相机帧率?
  • (2) 能否手动设置IMU帧率?
  • (3) 能否同时设置不同传感器/数据不同帧率?

这三个问题回答好了,那么上面提到的问题都可以解决了。经过相关文档阅读发现,相机和IMU设置帧率使用不同方法。本篇笔记首先关注相机的帧率设置,回答问题1和3。

1.相机传感器的进一步分析

这篇笔记中,我们学习了插入相机传感器,接着在这篇笔记中学习了利用ROS接口发布相机数据。而与相机帧率有关的就在Action Graph的相关设置中。如下,我们插入了一个相机,并且构建了Action Graph用于发布Topic。 可以看到,在当前配置下,Isaac Sim发布的默认影像帧率大约是60帧左右。这个帧率不是固定的,而是根据硬件配置而决定,可以理解为在当前硬件下,仿真环境能跑到的最高帧率。整个过程的核心是ROS Camera Helper。而这个过程更进一步是通过SGDPipeline实现的。当运行一次仿真环境以后,我们可以点击Action Graph面板左上角的小图标,然后选择SDGPipeline就能够看到了,如下。 打开的SDGPipeline如下所示。 我们之后手动设置帧率,其实就是手动修改这个Graph。所以在进一步介绍之前,不妨先简单了解一下这个SDGPipeline。首先需要说明的是,这个SDGPipeline是用于渲染仿真环境的,换句话说就是仿真的每一帧都会运行一遍这个Graph。其实最早接触这个概念是在我们学习Replicator的时候。把上面的SDGPipeline放大如下。

可以看到,整个Graph其实可以分为渲染和数据发布两个阶段。渲染始于Sd On New Frame,通过Sd On New Render Product Frame和Sd Render Var To Raw Array两个节点进行渲染。然后通过Isaac Simulation Gate控制是否执行,如果是的话,就利用Isaac RGBA to RGB节点进行数据转换,最后,利用ROS1 Publish Image节点进行数据发布。

在渲染阶段,每一帧都会经过这三个节点。事实上,渲染过程本身并没有帧率的概念。因为不管帧率是多少,反正SDGPipeline中的渲染会覆盖每一帧。而在数据发布阶段,SDGPipeline中也并没有提供显式的控制帧率的办法。但是有个关键节点叫做Isaac Simulation Gate,这个节点的作用就像一扇门,连接了渲染和数据发布过程。换句话说,如果我们认为控制这扇门的“开关”,那么就可以在一定程度上控制帧率。尽管渲染依然是逐帧渲染,但我们可以不逐帧发布(每隔N帧发布一次),这样就可以降低帧率了。而事实上Isaac Simulation Gate确实提供了Step属性,用来控制频率,如下所示。

2.修改相机帧率

在进一步介绍以前,再讨论一下两种不同的设置帧率的方式。一种就是我直接指定帧率/每帧多少时间,比如每帧50ms,那么1s就是20帧。另一种方式就是,指定数据帧发布的间隔,比如我现在每秒有100帧数据,但我指定每隔5帧发布一次,那么这样结果就是1s发布20帧。 在Isaac Sim中,从官方给的示例来看,似乎并不直接支持第一种方式,直接指定帧率或者每帧时间。它支持的是第二种,每隔N帧发布一次。核心就是通过修改SDGPipeline来实现,这里官方又给出了两种方法,效果是一样的,下面分别介绍。

2.1 基于Isaac Simulation Gate的帧率控制

前面说了,在SDGPipeline的Isaac Simulation Gate节点里有Step属性,可以通过设置它来改变帧率。所以当我们按照常规流程插入相机并搭建好Action Graph以后,运行一下就有了SDGPipeline。这时我们可以利用rqt工具监测一下当前的影像帧率有多少。比如,如下图所示,在我电脑上,当前的帧率约为75FPS。 而我的目标帧率是20FPS,那么我就需要大约每4帧发布一次,那么这里的Step属性就为4。修改完成以后,如下。修改帧率的时候不需要停止仿真环境,所有修改都是实时的。 可以看到,此时的帧率就大约变为20左右了。需要注意的是,这里发布的帧率其实每次运行都可能会有些许变化,不是完全固定的。比如第一次运行帧率为60左右,然后设置间隔为3,目标帧率就为20,但再次运行的时候,可能此时的帧率就变成了70,而间隔还是3的话,目标帧率就为23左右了。为了避免这种情况的出现,一个小技巧就是,直接启动仿真环境,根据运行的帧率实时调整间隔,这样就尽可能准确地控制帧率了,避免不同次运行帧率差异给间隔带来的影响。另外,我们几乎不可能完全帧率不变的采集数据,只要控制在合理范围内即可。

官方给的例子实现思路是一样的,只是它是基于Standalone模式写代码实现的。代码文件可以在Omniverse的安装目录下的/Libs/isaac_sim-2022.1.1/standalone_examples/api/omni.isaac.ros_bridge/目录下找到,叫做camera_periodic.py,如下。 可以看到,代码中就是通过指定Step属性来控制帧率的。代码中的这一段注释写的很好,说明了这种方法的实现,这里摘录出来:

Inside the SDGPipeline graph, Isaac Simulation Gate nodes are added to control the execution rate of each of the ROS image and camera info publishers. By default the step input of each Isaac Simulation Gate node is set to a value of 1 to execute every frame. We can change this value to N for each Isaac Simulation Gate node individually to publish every N number of frames.

2.2 基于Branch的帧率控制

另一种方法同样是修改SDGPipeline,但方式略有不同。上面我们用的是Isaac Simulation Gate节点,但我们还可以用另一种节点,叫Branch,也是用来控制流程的。这个节点的作用是,当某种条件被满足的时候会输出True,否则输出False。所以基于Branch的思路是,我们在Isaac Simulation Gate和后续节点之间插入Branch节点。当满足某种条件时才设为True,后续流程才会执行,这样也可以间接地实现帧率的控制。官方给的例子基中的一段注释很好,这里也摘抄过来:

Re-route the execution connections in between each of the IsaacSimulationGate nodes and their downstream nodes to make them run through branch nodes. Since the SDGPipeline graph runs every frame, a branch node can act as a custom gate for our publishers. When the condition input of the branch node is set to True, the downstream nodes will operate whenever the IsaacSimulationGate node triggers an execution. By default the condition input of a branch node is set to False.

代码文件可以在Omniverse的安装目录下的/Libs/isaac_sim-2022.1.1/standalone_examples/api/omni.isaac.ros_bridge/目录下找到,叫做camera_manual.py,如下。 可以看到,首先,通过代码,断开了Isaac Simulation Gate和后续节点之间的连接,并且在其中插入了Branch节点。然后,通过代码动态设置Branch节点的Condition来开启/关闭后续流程,把Branch节点的True输出和后续流程相连,如下。 可以看到,在while循环中引入了frame累计变量。对于RGB影像而言,如果这个frame变量能够被5整除,那么就将当前Branch节点的Condition属性设为True,这样就会执行后续流程。否则,什么都不做,因为在while循环中,Branch节点的Condition属性每次都会被初始化为False。通过这种方式,就可以轻易地实现每间隔N帧发布一次数据的目标,而且和上面的效果是一样的。

这种方法的缺点是在Action Graph中很难实现对于条件的判断,因此状态的动态控制并不容易操作,必须以standalone方式写代码才能实现。比如在上面的控制中,需要新建frame累加变量,但在Action Graph中,并不能够新建此类变量(也许可以但我不会,欢迎讨论)。优点是通过对特定的条件进行判断来控制是否发布数据,显然比设置间隔更加灵活。比如可以设置条件为仿真小车在特定区域才会发布数据,在这个区域之外不会发布这种条件等。,只能依赖写代码才能实现。

2.3 小结

至此,我们可以回答文章开头的第一个问题了。那就是Isaac Sim中,能否以及如何设置相机数据发布的帧率?首先答案是肯定的,可以设置。但需要注意的是,Isaac Sim中只支持间隔N帧发布一次这种方式,而不支持直接设置间隔n时间发布一次。设置发布数据帧率的核心是SDGPipeline,具体的设置方式有两种,一种是基于修改Isaac Simulation Gate节点的Step属性;另一种是在Isaac Simulation Gate和下游节点之间插入Branch节点,控制下游流程的执行。需要注意的是第一种方式直接修改Action Graph或者写代码都可以实现,而第二种只能通过写代码的方式实现。所以如果不想写代码,个人更推荐使用第一种方式,更加直观一些。

3.设置不同帧率

在实际应用中还有一个需求,那就是不同数据可能需要设置不同的发布帧率。比如RGB影像20FPS,深度影像10FPS,相机的CameraInfo只有1FPS。要实现这种目标,其实和上面介绍的是一样的。不同之处就在于,我们需要在Action Graph中分别构建出RGB影像、深度影像和相机信息的Pipeline,然后再在SDGPipeline中的对应Isaac Simulation Gate中修改Step属性即可。

3.1 构建RGB影像发布Pipeline

如下,是常规的RGB影像发布的Pipeline。 之前提到过很多次,此处就不再赘述,如果还不清楚可以翻之前的笔记。

3.2 构建深度影像发布Pipeline

深度影像其实在Isaac Sim中和RGB影像没什么本质区别,都是通过Camera对象获取的,只是数据类型不同。在ROS1 Camera Helper节点中有个type属性,把它修改成depth即可,所以构建的Graph如下。 运行一下就可以看到实时发布出来的深度图了。

3.3 构建相机信息发布Pipeline

有了前面的基础,相信你应该已经猜到了。发布相机信息,我们只需要把ROS1 Camera Helper节点的type属性改成CameraInfo即可,如下。

3.4 设置不同帧率

我们构建好的三种相机数据总的Action Graph如下。 这里我为了方便,三个Topic共用了一个相机,换句话说就是一个视角/相机同时发布RGB、深度和相机信息,深度图和RGB还是严格对齐的(这在实际传感器中其实并不好做,但仿真环境却可以很容易实现)。当然,你可以每个发布节点新建一个Viewport和相机,没问题。点击运行仿真环境以后,我们就会生成SDGPipeline,打开如下。 可以看到这里有三个Isaac Simulation Gate,根据前面的知识,我们只需要依次修改它们的Step属性即可。比如我这里最高帧率约为60左右,我们期望RGB帧率是20,深度为10,相机信息为1,这样步长分别为3、6、60,设置好以后运行如下。 这样,便完成了对不同数据不同帧率的设置。当然这里需要注意的是对SDGPipeline的修改不是永久的,它不会随项目保存。当打开一个项目以后,我们需要先运行一下仿真环境,才会生成SDGPipeline。当关闭Isaac Sim以后,它就失效了。当然,只要不关闭Isaac Sim,停止或重新运行仿真环境是不会影响SDGPipeline的。

3.5 小结

至此,开头的第三个问题:能否同时设置不同传感器/数据不同帧率?答案是肯定的,可以设置不同帧率。而至于如何设置,本质上还是依靠SDGPipeline,通过修改Isaac Simulation Gate的Step属性实现。不同的Publisher有不同的Gate,分别设置想要的发布间隔即可。 最后说说为什么IMU不能这样设置呢?因为这里所有的设置其实都和Camera Helper有关或者说是依赖GPU渲染的,所以通过修改SDGPipeline就可以实现。而IMU是物理传感器,并不通过SDGPipeline进行数据发布,自然也就不能通过修改它来实现帧率的设置。IMU需要通过修改场景的物理刷新率(与仿真环境的渲染帧率不同)进行设置,比如在官方的这个例子中提到这一点。这些问题在之后的笔记中再详细讨论。

4.参考资料

  • [1] https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/tutorial_ros_python.html#ros-camera

本文作者原创,未经许可不得转载,谢谢配合

返回顶部