相机和图像的工作原理

尽管在 ROS 中第一次让相机工作是一件令人兴奋的事情,并且很容易急于前进,但如果我们先了解一些理论背景,尤其是当你对这些内容不太熟悉时,事情会更容易理解。这个主题非常广泛,有些人甚至会专门为此攻读大学学位,因此这里的笔记实际上只是一个概述。

相机的类型

当你想到相机时,可能会有某种具体的印象。相机直接观察它面前的世界,并将其转换为一个二维的彩色像素网格。尽管这正是我们在本教程中主要使用的相机类型,但值得承认的是,市场上存在着各种各样的相机。相机的几种变化方式包括:

传感器类型(例如:彩色、单色/灰度、热成像、红外)

  • 光学系统 Optics(例如:鱼眼镜头、宽视场、360度视角、焦距)
  • 帧率 Frame rate(例如:高速相机)

这些因素都影响相机的性能和应用,因此了解这些基础知识对使用和选择合适的相机是非常重要的。

本教程中涵盖的大多数概念在某种程度上都适用于所有这些相机。

其中一种特定类型的相机是深度相机,我们将在下一节教程中深入探讨(字面上的“深度”)。
但请务必先阅读这一节,因为它将作为后续内容的基础。

捕捉与存储图像

当相机拍摄图像时,光线穿过镜头和光圈,最终到达传感器。这些数据被记录并存储为像素 pixels。图像就是在传感器上每一点光强度的二维数组。

对于灰度图像来说,这个过程相对简单——每个像素有一个光强度测量值。但对于彩色图像来说,情况会复杂一些。有几种不同的方法可以实现彩色图像的存储,但在计算机上最常用的方法是将颜色信息分为三个不同的通道——红色、绿色和蓝色。通过组合这些基础颜色的不同量,我们可以生成几乎任何颜色。没有任何颜色的情况下是黑色,所有三种颜色的最大值组合是白色,其他介于两者之间的颜色则由这三种颜色的不同组合产生。

最常用的是每个颜色通道每个像素使用8位,这样每个通道有256种不同的值,最小为0,最大为255。通常我们按照红色、绿色、蓝色的顺序来排列这三种颜色,简称RGB。

有时候,你可能会遇到其他模式。例如,相机可能会给你每像素16位的数据,或者使用像OpenCV这样的库,它将数据存储为BGR。在任何情况下,整体原理是相同的。

图像压缩

这种格式(每个像素3个8位值)对于计算机来说非常容易处理,但在空间利用上并不高效,因此我们通常会使用压缩。这在通过网络发送图像消息时尤其重要,这是机器人技术中的一种常见过程。

为了节省空间,我们可以简单地调整图像大小,丢弃一些像素,但像JPEG和PNG这样的格式可以更智能地处理数据,它们在不缩小实际图像的情况下减小数据大小——不会丢失任何像素。计算机使用一些巧妙的算法来丢弃不太重要的信息。例如,如果有一个大块黑暗区域,计算机可以将这些像素组合在一起,而不是为每个像素存储“0红色、0蓝色、0绿色”。PNG以一种不丢失任何信息的方式执行压缩,而JPEG则是有损的,有时相邻的像素可能会有些许融合。

焦距

许多参数都会影响相机的最终图像,但值得基本了解的是焦距 (focal length)。这是相机内传感器与镜头之间的距离,但如果不知道传感器的大小,这个距离本身没有多大意义。通常我们更容易讨论水平视场角 (horizontal field-of-view, HFoV),即从图像左侧到右侧的角度。

当我们增加焦距时,视场角会变小,使这个角度更紧凑,这就是所谓的放大。在下图中,你可以看到大焦距的情况下,相机只能看到人物上方的一部分,而不是所有的树木。

在机器人技术中,我们通常希望尽可能多地看到周围的环境,因此我们使用的是视场角较宽或焦距较短的相机,以便于获取更广泛的视野。

如果你需要进行焦距转换,这里有一个方程,实际上就是一些基本的三角函数计算。

h _ f o w = 2 t a n − 1 s e n s o r _ w i t h 2 × f o c a l _ l e n g t h h\_fow=2tan^{-1} \frac{sensor\_with}{2 \times focal\_length} h_fow=2tan12×focal_lengthsensor_with

请注意,图示并不完全按比例绘制,也不完全准确地描述了镜头与传感器的交互,但希望它能帮助你理解焦距调整的效果。欲了解更多详细信息,请查阅维基百科和相关链接。

坐标系

最后需要简要提到的是坐标系统。在处理图像时,通常 X 方向是从左到右,Y 方向是从上到下。根据右手规则,这将导致 Z 方向垂直于页面(或从相机向前指向)。当我们查看 ROS 如何处理这些内容时,这一点会再次出现。

ROS 中的相机和图像

现在我们对图像和相机的工作原理有了大致了解,让我们看看它们在 ROS 中是如何使用的。

相机驱动节点和图像消息

首先,就像前一篇文章中的 LIDAR 一样,我们总是会有一个相机驱动节点。这是一个旨在与特定相机硬件通信并发布数据流的节点。驱动节点通常能够控制相机流的各种方面,例如分辨率和帧率。

然后,这个驱动节点将来自相机的数据流发布到类型为 sensor_msgs/Image 的话题上。就像我们看到的 LIDAR 一样,这意味着算法只需要编写来处理图像消息,只要你的相机有一个驱动程序,它就能工作,这很好。请注意,还有另一种类型叫做 sensor_msgs/CompressedImage,它用于处理压缩图像。

相机驱动直接发布的未处理图像话题通常称为 /image_raw(以表示未处理的图像,不要与专业摄影中使用的 RAW 格式混淆)。如果有压缩版本,它会在基础话题的末尾添加 /compressed——所以在这种情况下,它将是 /image_raw/compressed

为了处理压缩,ROS 提供了 image_transport 工具。如果节点编写得当,image_transport 可以自动处理所有的压缩/解压缩问题。如果节点编写不正确(例如,驱动程序只发布了压缩图像),image_transport 提供了自己的节点来“填补空白”,我们稍后将进行探讨。

请注意,Image 消息有一个 Header,包含图像测量的时间和拍摄图像的相机的坐标系信息。

相机信息

ROS 提供了另一种类型,叫做 sensor_msgs/CameraInfo。它提供了关于相机的各种元数据——例如镜头畸变等——以便算法可以正确解释图像数据。这个话题通常称为 /camera_info,与图像话题在同一个命名空间中,例如 /my_camera/image_raw 对应 /my_camera/camera_info

在本教程中,我们不会花更多时间查看相机信息。

ROS 提供了 image_proc/image_pipeline 包来帮助将 /image_raw 话题转换成更有用的数据,这些数据通常会发布到如 /image_color/image_rect 等话题上。虽然这超出了本教程的范围,但你可能会发现CameraInfo 文档ROS 1 image_proc 文档 非常有用。

坐标系

在 ROS 中处理相机时,坐标系的使用常常让人感到困惑。

为了让相机数据正确处理,它需要与一个坐标系关联——这没什么大不了的。但坐标系应该是什么方向呢?我们在之前的教程中看到,在 ROS 中,标准的方向是 X 向前,Y 向左,Z 向上。然而,正如我们刚才看到的,标准的图像和相机坐标系是 X 向右,Y 向下,Z 向前。

为了适应这一点,标准的方法是创建两个位于相同位置的坐标系,一个命名为 camera_link(遵循 ROS 的命名规范),另一个命名为 camera_link_optical(遵循标准的图像命名规范)。ImageCameraInfo 消息头应引用 camera_link_optical 坐标系,但如果需要的话camera_link 仍然存在。

我们将在更新 URDF 文件时很快看到这一点的实际应用。

在 Gazebo 中模拟相机

就像在前一教程中处理 LIDAR 一样,我们将在尝试连接真实相机之前,首先在 Gazebo 中模拟并使相机正常工作。如果有些概念讲得太快,可以查看那篇教程以获得进一步的解释。

## 向 URDF 添加相机 link/joint 我们将以类似于 LIDAR 的方式开始(以至于你可以直接复制 lidar.xacro 并替换一些名称):
  • 创建一个新的文件,命名为 camera.xacro,放在描述目录中。
  • 添加 <robot> 标签。
  • robot.urdf.xacro 中添加 <xacro:include filename="camera.xacro" />
  • 创建一个名为 camera_link 的链接和一个名为 camera_joint 的关节,连接(固定)到底盘上。

在这个示例中,相机的原点将位于底盘的前中心(X 方向前移 305mm,Z 方向上移 80mm)。注意,此时我们仍然遵循 ROS 的“X 向前”惯例。我没有添加任何旋转,因为我的相机正面朝前,但如果你的相机有倾斜,你可以添加适当的旋转。

<joint name="camera_joint" type="fixed">
    <parent link="chassis"/>
    <child link="camera_link"/>
    <origin xyz="0.305 0 0.08" rpy="0 0 0"/>
</joint>

我们可以添加一个名为 camera_link 的链接标签,并设定一些视觉属性。在这个示例中,我们将相机表示为一个小的红色矩形棱柱体。

<link name="camera_link">
    <visual>
        <geometry>
            <box size="0.010 0.03 0.03"/>
        </geometry>
        <material name="red"/>
    </visual>
</link>

由于我的相机很小并且固定在底盘上,所以我跳过了碰撞和惯性参数。如果你的相机从底盘突出来,它可能需要碰撞参数;如果相机不是固定在一个关节上,它还需要惯性参数。

另外,记得添加一个 标签来指定材料颜色。

<gazebo reference="camera_link">
    <material>Gazebo/Red</material>
</gazebo>

添加 link/joint

接下来,我们需要添加一个虚拟“dummy”链接,称为 camera_link_optical,以适应不同的坐标系标准——从 ROS 标准的机器人方向(X 向前,Y 向左,Z 向上)转换到光学标准的方向(X 向右,Y 向下,Z 向前)。

对于一个名为 camera_link 的相机链接,以下块实现了这一点,可以放置在文件的任何位置。

<joint name="camera_optical_joint" type="fixed">
    <origin xyz="0 0 0" rpy="${-pi/2} 0 ${-pi/2}" />
    <parent link="camera_link" />
    <child link="camera_link_optical" />
</joint>

<link name="camera_link_optical"></link>

如果现在重新构建并运行,你会看到以下结果(注意,此时你可能需要将 <visualize> 设置为 false 以避免干扰的蓝色线条)。

在 Gazebo 中模拟相机

现在,我们已经设置了链接和关节,可以在 <gazebo> 标签中添加 <sensor> 标签,以告诉 Gazebo 模拟一个相机。请注意,这里是为 camera_link 添加的 Gazebo 标签,而不是光学标签。

这与上一教程中的 LIDAR 类似,我们需要:

  • 一些所有传感器共有的内容
  • 针对相机传感器的特定参数
  • 一个 ROS 插件

唯一的变化是传感器的类型(及名称),现在是相机,插件的文件名(及名称),我们将稍后详细介绍。

<sensor name="camera" type="camera">
    <pose> 0 0 0 0 0 0 </pose>
    <visualize>true</visualize>
    <update_rate>10</update_rate>
    <camera>
        ...填入下一节内容...
    </camera>
    <plugin name="camera_controller" filename="libgazebo_ros_camera.so">
        ...填入下一节内容...
    </plugin>
</sensor>

如果这些内容让你感到困惑,建议回顾 LIDAR 教程。现在,让我们探索一下不同之处。首先是 <camera> 标签中的参数。我设置了以下内容:

  • 水平视场角为 1.089 弧度,大致匹配 Pi 相机
  • 图像大小为 640x480 像素,存储为 8 位 RGB
  • 剪裁平面(相机可见的距离)设置为最小 0.05 米和最大 8 米
<camera>
    <horizontal_fov>1.089</horizontal_fov>
    <image>
        <format>R8G8B8</format>
        <width>640</width>
        <height>480</height>
    </image>
    <clip>
        <near>0.05</near>
        <far>8.0</far>
    </clip>
</camera>

最后是 <plugin> 标签。这个标签是我们将数据输入和输出到 Gazebo 的方式(在这个案例中,通过 libgazebo_ros_camera.so 插件传输到 ROS)。这个插件与 LIDAR 插件类似,但稍微简单一些。我们需要设置的唯一参数是 frame_name,这次需要设置为 camera_link_optical(而不是 camera_link)。这将确保图像话题的 Header 正确设置。

<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
    <frame_name>camera_link_optical</frame_name>
</plugin>

现在,我们可以重新启动 Gazebo,我们将模拟一个相机!由于 visualize 设置为 true,我们可以看到相机的预览。如果我们在场景中添加一些物体,可以看到相机能够看到这些物体。详细代码中论文最后

这表明相机在 Gazebo 中工作正常,但我们怎么知道它是否成功发布到 ROS 的其他部分呢?

可视化相机数据

当我们想检查图像数据是否正确发布时,通常使用 ros topic echo 并不实际,我们想看到实际的数据。

要检查相机是否正确模拟,可以启动 RViz 并添加一个图像部分。将话题设置为 /camera/image_raw,并确保 Fixed Frame 设置为你机器人上的某个链接(例如 base_link,如果那不起作用,可以尝试 camera_link)。

注意,我过去遇到过 QoS 不允许查看数据的问题。如果你遇到麻烦,可以尝试将可靠性策略更改为 Best Effort

希望你能看到一个小窗口显示我们的模拟世界!

RViz 还提供了 Camera 显示功能,它类似于上述功能,但将图像叠加在世界的 3D 视图上。如果我们在 RViz 中展示了其他内容(例如其他机器人的模型),并且所有内容都经过了正确的校准和去畸变,这将帮助我们检查所有内容是否对齐。

你还可以尝试其他几个节点来查看数据,比如 image_viewrqt_image_view,它们有时比 RViz 更加稳定,特别是在处理坐标变换和图像压缩时。

Pi Camera V2 相机连接

现在我们已经成功模拟了一个虚拟相机,接下来可以尝试设置一个真实的相机。对于这个示例,我将使用 Pi Camera V2。

注意:以下指示并不是唯一的实现方法,实际上可能并不是最佳方法,因为它们不允许完全控制相机(例如灵敏度、快门速度等),只是我用过的一种可行的方法。

连接设备

在开始之前,我们需要安装一些软件包(你可能还想安装 rqt_image_view):

sudo apt install libraspberrypi-bin v4l-utils ros-foxy-v4l2-camera ros-foxy-image-transport-plugins

此外,使用 groups 命令确认你已在视频组中(以允许相机访问)。如果不在,运行 sudo usermod -aG video $USER(这需要注销/重启才能生效)。

接下来,关闭 Pi,将相机连接上。将一端的排线插入板上的端口,另一端插入相机。查看以下图片以确保连接方向正确(排线上的蓝色部分应与连接器上的黑色夹子在同一侧)。

然后可以重新启动 Pi。首先,检查 Pi 是否检测到相机:

vcgencmd get_camera

应该会看到 supported=1 detected=1 的响应。

如果 Pi 连接了显示屏,这是一个测试相机是否正常工作的好机会!可以运行 raspistill -k,相机流将显示在屏幕上,然后按 x回车键退出。

接下来,可以运行:

v4l2-ctl --list-devices

应该会有一个 mmal service, platform bcm2835-v4l2, device /dev/video0 的条目。这表明 V4L2 子系统能够识别相机,这意味着我们可以继续下一步!

运行驱动节点

要运行 V4L2 驱动节点,使用以下命令,这将正确设置帧 ID(确保你已关闭 Gazebo!),并设置图像大小。请注意,这个驱动程序目前无法限制帧率,但未来的更新可能会支持。你还可以将话题重新映射到与 Gazebo 匹配的名称。

ros2 run v4l2_camera v4l2_camera_node --ros-args -p image_size:="[640,480]" -p camera_frame_id:=camera_optical_link

以下是 rqt_image_view 中显示的 /image_raw 输出的示例。

Launch 文件

为了简化操作,我们可以将所有内容打包成一个启动文件,如下所示:

import os
from launch import LaunchDescription
from launch_ros.actions import Node

def generate_launch_description():
    return LaunchDescription([
        Node(
            package='v4l2_camera',
            executable='v4l2_camera_node',
            output='screen',
            parameters=[{
                'image_size': [640,480],
                'camera_frame_id': 'camera_link_optical'
                }]
    )
    ])

解压和重新发布图像数据

最后,如果我们需要手动处理图像的压缩/解压缩,可以先检查 image_transport 安装了哪些插件:

ros2 run image_transport list_transports

然后,要重新发布一个话题,我们需要指定输入和输出的类型。我们还需要重新映射一些话题,格式为 {in/out}/{type}(对于未压缩/原始图像没有类型)。例如,从压缩输入话题重新映射到原始输出话题的命令是:

ros2 run image_transport republish compressed raw --ros-args -r in/compressed:=/camera/image_raw/compressed -r out:=/camera/my_uncompressed_image

注意:在 image_transport 中,原始 raw 意味着“未压缩”,与 image_raw 中的原始 raw 无关。

结论

现在我们了解了相机和图像在 ROS 中的工作原理,能够在 Gazebo 中模拟相机,并连接到真实相机。在下一个教程中,我们将继续探讨相机,特别是深度相机,它还会返回每个像素的距离信息。

完整的 camera.xacro 如下:

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" >

    <joint name="camera_joint" type="fixed">
        <parent link="chassis"/>
        <child link="camera_link"/>
        <origin xyz="0.305 0 0.08" rpy="0 0 0"/>
    </joint>

    <link name="camera_link">
        <visual>
            <geometry>
                <box size="0.010 0.03 0.03"/>
            </geometry>
            <material name="red"/>
        </visual>
    </link>


    <joint name="camera_optical_joint" type="fixed">
        <parent link="camera_link"/>
        <child link="camera_link_optical"/>
        <origin xyz="0 0 0" rpy="${-pi/2} 0 ${-pi/2}"/>
    </joint>

    <link name="camera_link_optical"></link>



    <gazebo reference="camera_link">
        <material>Gazebo/Red</material>

        <sensor name="camera" type="camera">
            <pose> 0 0 0 0 0 0 </pose>
            <visualize>true</visualize>
            <update_rate>10</update_rate>
            <camera>
                <horizontal_fov>1.089</horizontal_fov>
                <image>
                    <format>R8G8B8</format>
                    <width>640</width>
                    <height>480</height>
                </image>
                <clip>
                    <near>0.05</near>
                    <far>8.0</far>
                </clip>
            </camera>
            <plugin name="camera_controller" filename="libgazebo_ros_camera.so">
                <frame_name>camera_link_optical</frame_name>
            </plugin>
        </sensor>
    </gazebo>

</robot>

原文连接:https://articulatedrobotics.xyz/tutorials/mobile-robot/hardware/camera/

Logo

有“AI”的1024 = 2048,欢迎大家加入2048 AI社区

更多推荐