NVIDIA Omniverse和Isaac Sim笔记5:Isaac Sim的ROS接口与相机影像、位姿真值发布/保存

Dec 16,2022   4718 words   17 min

Tags: Simulation

在之前的这篇笔记中,我们介绍了如何利用Synthetic Data Recorder保存数据。并且进一步在这篇笔记中,又通过键盘控制机器人,在一个仓库场景中进行了数据采集。但事实上,通过上面提到的方法进行数据采集,从SLAM角度而言至少有几个问题。第一,采集的影像帧没有对应的时间戳,系统默认是按照顺序依次增加的。第二,我们没有办法获取/保存机器人运动的轨迹真值,无法对位姿估计精度作评价。第三,如果你仔细观察保存的影像帧,会发现帧率非常低,大约仿真环境每输出6帧才会保存一帧影像,这显然对于SLAM是无法接受的。尽管第二个问题我们可以通过获取机器人对象的位姿属性,并将其输出到Isaac Sim控制台中,但这依然无法解决问题。因为没有办法和影像做时间对齐。面对上面的这些问题,一个有效的解决办法是利用Isaac Sim提供的ROS Bridge将数据发送出去,我们再用ROS的录制工具将这些Topic录制下来,这样就可以“完美”地实现我们的SLAM数据采集需求。当然,看到这里,你可能有预感,没错,我们要转移“阵地”了。我们要在Ubuntu下使用Isaac Sim。之前的笔记都是在Windows下的,而只有Ubuntu下的Isaac Sim才有ROS相关接口。不过好在其实Omniverse基本是平台无关的,所有界面和功能都是一样的。本篇笔记,我们首先会介绍Ubuntu下Omniverse的安装。然后以发送物体的位姿给ROS和发送相机的影像给ROS两个例子进行ROS相关借口的介绍。最后,我们以一个完整的实例来演示利用Isaac Sim进行数据采集、录制的全过程。

1.Ubuntu下Omniverse的安装

1.1 检查并更新显卡驱动

输入nvidia-smi查看GPU驱动版本,如下。 可以看到,目前的版本是465.19,低于之前笔记中提到过的Linux要求的470.57版本,所以要更新驱动。

首先输入sudo apt-get remove --purge nvidia*卸载现有驱动,如下。 可以看到,这个命令不仅卸载了显卡驱动,连同安装的CUDA也一并卸载了。

然后,输入sudo apt-get update更新仓库信息,如下。

然后,输入sudo ubuntu-drivers devices查看可以选择哪些驱动,如下。 可以看到,有多种显卡驱动可选。为了保险起见,我们可以选择比470高一些的驱动,比如515。

在终端中输入sudo apt-get install nvidia-driver-515,如下。 完成以后如下图所示。

最后,重启电脑。重启电脑以后,打开终端,输入nvidia-smi查询显卡驱动状态。 可以看到,显卡驱动就成功更新了,同时也装好了对应的CUDA。

1.2 Omniverse与Isaac Sim安装

在Ubuntu下的Omniverse安装和Windows下一样,按照之前这篇笔记说的,下载安装程序,直接运行即可。然后也可以像之前一样,安装Isaac Sim。安装完成以后就可以正常运行了(第一次启动似乎有些慢,可能要几分钟,稍作等待),如下。 这里需要注意的是Omniverse不支持以root账户运行,如果非要运行,需要在启动命令中加入--no-sandbox参数才可以。我的解决方法是,创建一个新的普通账户(因为root账户下已经装好了ROS等很多环境,在这个账户下直接用就可以了),然后在其中安装Omniverse并运行。

1.3 Isaac Sim启用ROS扩展

打开Isaac Sim以后,点击菜单中的Window->Extensions,然后在弹出的窗口中搜索ROS,找到ROS BRIDGE扩展启用即可,如下。当然,也可以把AUTOLOAD选项勾选。 这样,准备工作就完成了。

2.相机影像数据的发布

本部分主要参考这个官方文档,有所精简、修改。先总体介绍一下影像数据发布的流程。核心就是创建一个Viewport并把相机绑定到这个Viewport上,然后调用ROS1 Camera Helper将数据发送出来。还是比较简单的。

2.1 Action Graph构建

首先,我们新建一个空白场景,然后随便插入一些形状,并插入一个相机,取名叫Camera_test,如下图所示。 然后,我们新建一个Action Graph,添加Isaac Create Viewport节点。它的输入有两个,分别是触发信号和要新建的Viewport的ID。我们分别添加On Playback Tick和Constant Int(将其值设为1),并连接。它的输出也有两个分别是输出信号和构造好的Viewport,如下。 这样,当运行仿真环境的时候,系统就会自动创建一个新的Viewport。当然这里需要注意的是,对于某个Viewport,即使我们点击叉号把它关了,它并不是被删除了,只是被隐藏了起来。如果想找到它,点击菜单栏中的Window就能看到之前新建的Viewport。然后,我们再插入Set Active Camera节点。该节点有三个输入,分别是触发信号、Camera对象的Path以及要绑定的Viewport的名称。我们再新建一个Get Prim Path节点,并将其设为刚刚我们新建的相机Path,也即/World/Camera_test,注意要写全称。最后,再将Isaac Create Viewport节点的输出连接起来,如下。 最后,我们插入影像数据发送节点,ROS1 Camera Helper。它的输入有很多,但核心的就是触发信号、topicName和Viewport,其它在属性里都可以按需修改。我们可以新建一个Constant String节点指定要发布的Topic名称,比如叫/rgb_img。最后,我们把Isaac Create Viewport输出的Viewport连接到ROS1 Camera Helper的Viewport输入,把Constant String连接到TopicName,把Set Active Camera的输出信号连接到它的输入,如下所示。 这样,相机数据发布节点就搭建完成了。需要说明的是,ROS1 Camera Helper有个type属性,里面还可以选择如深度图、点云等其它数据格式,按需使用。另外,在发布Topic的时候,影像数据对应的Viewport要处于开启状态,不然会接收不到数据报错。

2.2 运行测试

新打开一个终端,运行roscore,然后再运行仿真环境。通过rqt_image_view工具就可以顺利可视化发布出来的Topic了,如下所示。 可以看到,我们的ROS节点顺利接收到了Isaac Sim发布的影像数据。通过rqt_graph工具也可以看到Isaac Sim发布Topic的节点,如下。 当然,你可能还有个困惑,我们目前没有设置过影像的帧率和大小,那现在是多少呢?我们可以通过rqt的topic monitor查看,如下。 可以看到,帧率大约在60左右,而长宽分别为1280和720。这些参数是在刚刚新建的Viewport的参数里可以修改的如下所示。 拿到影像的Topic以后,要做什么就随你喜欢了,比如将Topic录制保存下来等的。这样,我们便完成了Isaac Sim相机影像数据的发布。另外需要说明的是,Isaac Sim本身支持对于噪声的仿真,感兴趣可以参考这个官方文档

3.机器人位姿真值发布

本部分主要参考这个官方文档,有所精简、修改。还是先简单介绍一下主要流程。首先我们要获取到Odometry相关信息,这需要Isaac Compute Odometry Node完成,然后利用ROS1 Publish Odometry把数据发布出去。当然,为了有正确的时间戳,还需要Isaac Read Simulate Time来提供精确的时间(如果没有这个节点,发布的位姿消息的时间戳都为0)。

3.1 Action Graph构建

我们还是按照之前的例子,新建一个场景,然后插入一个Jetbot,如下。 然后新建Action Graph,插入Isaac Compute Odometry Node,在它的inputs:chassisPrim属性中选择要发布位姿的物体。比如我们可以直接发布Jetbot的/World/jetbot/chassis(注意写全称)。它的输出则是我们想要的了,包括计算好的角速度、线速度、姿态、位置,如下。 然后再插入ROS1 Publish Odometry节点,设置输出Topic的名称(topicName属性,默认为odom)。再将Isaac Compute Odometry Node对应的输出连接起来,如下。 然后,再插入Isaac Read Simulation Time,将正确的时间戳赋给要发布的Topic,如下。 最后,我们插入On Playback Tick节点,触发整个Action Graph,如下。 这样,我们的Action Graph就构造完成了。

3.2 运行测试

新打开一个终端,运行roscore,然后再运行仿真环境。然后通过rostopic echo /odom即可查看发布出来的Topic内容,如下所示。 可以看到,ROS已经正确接收到了发布出来的位姿信息。我们也可以检查一下发布的帧率,如下。 可以看到,默认帧率在100左右。当然,你完全可以在Action Graph中增加控制节点,如下。 实际控制如下所示,这样就能更直观的感受位置变化。 至此,我们便完成了对于机器人位姿真值的发布。

4.实际例子

上面,我们分别发布了机器人获取的影像以及对应的位姿真值。我们完全可以把这两个功能结合起来,形成真正可用的采集环境。一个完整的Action Graph如下图所示。 总体看起来比较复杂,但其实分部分看也很容易理解,主要分为键盘控制(前后)、键盘控制(左右)、影像Topic发布和位姿Topic发布四个部分。运行这个仿真环境,实际效果如下。 可以看到,Isaac Sim实时输出了机器人采集的影像和位姿真值。拿到了这些我们就可以利用ROS bag工具把它们保存下来。下图是保存下来的Bag文件相关信息。 可以看到分别包含位姿和影像。我们可以用rqt bag工具检查一下时间戳情况,如下。 可以看到,位姿和影像Topic是在同一个时间基准下面的。至此,我们便完成了利用Isaac Sim采集SLAM数据的全部流程,包括场景搭建、机器人控制、影像数据输出/保存、位姿真值输出/保存。

5.参考资料

  • [1] https://blog.csdn.net/qq_43744723/article/details/123959160
  • [2] https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/tutorial_ros_camera.html
  • [3] https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/tutorial_ros_tf.html
  • [4] https://docs.omniverse.nvidia.com/app_isaacsim/app_isaacsim/tutorial_ros_camera_noise.html#isaac-sim-app-tutorial-ros-camera-noise

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

返回顶部