英特尔 RealSense T265

本文将介绍如何设置 英特尔 Realsense T265 与 ArduPilot 一起使用,作为 GPS 的替代品,允许 Loiter、PosHold、RTL、Auto 等定位控制模式工作。该方法使用在 RPI 配套计算机上运行的 python 脚本向 ArduPilot 发送位置信息,而无需使用 ROS.......。 使用 ROS 的设置在这里.

购买什么

备注

RPI4 支持 USB3,可同时实现以下功能 姿势 + 图像 从摄像头采集数据。速度较慢的 RPI3 只有 USB2 接口,这意味着只有 姿势 尽管这对大多数用户来说已经足够,但仍可采集数据。

硬件设置

./_images/t265-rpi4-pixhawk.png
  • 下载最新的 APSync Ubuntu 映像 (在这里找到)到个人电脑,然后使用以下工具将其闪存到 16GB (或更大)的 SD 卡中,如 蚀刻机Win32DiskImager 然后将其插入 RPI 的 SD 卡插槽中

  • 将英特尔 RealSense T265 安装在载具上,面向前方(有关其他方向的信息,请参阅下文),使用厚双面胶带或其他工具。 大卫-萨斯特雷的 T265 坐骑 以更好地隔离相机的震动

  • 将英特尔 RealSense T265 的 USB 电缆连接到 RPI4 的一个蓝色 USB3 端口上

  • 将 PiConnectLite 的电源线连接至电池(7V 至 30V)

  • 将 PiConnectLite 的串行电缆连接到(飞行)控制器的一个遥测端口(即 Telem1、Telem2)。该电缆中使用的信号只有 TX、RX 和 GND。其他信号为 NC。

../_images/t265-mount.png

大卫-萨斯特雷的 T265 坐骑

配置 ArduPilot

用地面站(如Mission Planner地面站)连接(飞行)控制器,检查是否设置了以下参数:

  • serial2_protocol = 2 (MAVLink2)。请注意,前提是 RPI4 连接到 AutoPilot "Telem2 "端口。

  • SERIAL2_BAUD = 921(921600 波特)

  • 可选择设置 serial2_options = 1024(不转发导航链路到/从)以阻止 RPI4/T265 导航链路信息再次到达地面站

  • VISO_TYPE = 2 (IntelT265)

接下来设置 EKF3,使用 ExternalNav 获取位置和速度:

如果要使用相机的航向:

如果您希望使用(飞行)控制器的罗盘确定航向:

  • COMPASS_USE = 1(默认值)

  • EK3_SRC1_YAW = 1(指南针)

  • RC7_OPTION = 80(Viso Align),允许飞行员在飞行前使用辅助开关 7 将相机偏航与 AHRS/EKF 偏航重新对齐。起飞前重新调整偏航是个好主意,否则可能会发生位置失控(又名 "厕所保龄球")。

修改参数后,重启(飞行)控制器。与地面站连接,(如果使用Mission Planner地面站)在地图上单击鼠标右键,选择 "在此设置原点"、"在此设置 EKF 原点",告诉 ArduPilot 载具的位置,它就会立即出现在地图上。

飞行前,将飞行器升至 1 米高,然后再放下。这可以让相机校准其垂直缩放比例。

如果您希望在 GPS 和 T265 之间切换,请参阅 GPS/Non-GPS 转换 维基页面

系统概述

./_images/ros-vio-connection.png

简而言之,6-DOF 姿态数据 (位置方向)和 置信水平 从 Realsense T265 获取的数据将由我们的 python 脚本处理,并通过 MAVLink 发送至 ArduPilot。总的来说,脚本将完成以下任务:

  • 使用相关应用程序接口从以下设备获取 6-DOF 姿态数据和跟踪置信度数据 pyrealsense2的 Python 封装器。 librealsense.

  • 执行必要的矩阵变换,以对齐 Realsense T265 和 NED 的帧以及其他处理步骤。

  • 将姿态数据打包到 MAVLink 信息中 视觉位置估计 和置信度数据到假信息中,然后以预定的频率将它们发送到 ArduPilot,以免 洪水 (飞行)控制器输入数据。

  • 自动设置 EKF 起始点,方便设置和飞行。

备注

Python 的选择是可选的,您可以使用任何 librealsense 支持的其他封装器.ROS 用户可以找到相应的文章 这里.

备注

为简洁起见,对系统的解释将尽量简短。更深入的讨论可参见以下博文: 第四部分, 第五部分.

安装 librealsensepyrealsense2

Realsense T265 通过以下方式提供支持 librealsense 在 Windows 和 Linux 上运行。不同系统的安装过程差异很大,因此请参考 官方 Github 页面 了解具体系统的说明:

对于运行 Ubuntu 的 RPi,安装程序为 librealsense本维基.按照说明安装 librealsensepyrealsense2.因为我们 使用 ROS、 真-罗斯 不需要。

安装 Python 软件包

# 更新 PYTHONPATH 环境变量,添加 pyrealsense2 库的路径
出口 飞龙之路=$PYTHONPATH:/usr/local/lib

CD ~/librealsense/wrappers/python/examples

# 你应该看到从 T265 传出的数据流。
python3 t265_example.py
# pip install 可能需要 sudo,请照此进行
核心 安装 pyrealsense2 pip3 安装 转换 pip3 安装 dronekit pip3 安装 apscheduler

# 为串行连接安装串行软件包
苏都 管道3 安装 串行
# 导航至脚本的位置
CD ~/path/to/the/script/

# 如果还没有下载脚本,请下载:
wget https://raw.githubusercontent.com/thien94/vision_to_mavros/master/scripts/t265_to_mavlink.py chmod +x t265_to_mavlink.py

如何运行

  • 在运行脚本之前 飞龙之路 环境变量,并将其路径添加到 pyrealsense2 库。或者,复制构建输出 (librealsense2.sopyrealsense2.so~/librealsense/build/) 旁边的脚本。首先,运行测试脚本 t265_test_streams.py 以验证 pyrealsense2 并连接 T265。

# 更新 PYTHONPATH 环境变量,添加 pyrealsense2 库的路径
出口 飞龙之路=$PYTHONPATH:/usr/local/lib

# 导航至脚本的位置
CD ~/path/to/the/script/

# 下载并运行测试脚本,您应该能在终端上看到来自 T265 的姿势数据短流
wget https://raw.githubusercontent.com/thien94/vision_to_mavros/master/scripts/t265_test_streams.py chmod +x t265_test_streams.py python3 t265_test_streams.py
  • 修改 t265_to_mavlink.py 系统配置的脚本。最重要的是,找到并更改脚本中的以下参数:

# 连接 FCU 的默认配置
默认连接字符串 = '/dev/ttyUSB0'
默认连接波特率 = 921600

# 姿势和信心信息的默认频率
vision_msg_hz_default = 30
置信度_msg_hz_default = 1

# 将不同的摄像机方向转换为 NED 标准。根据配置替换 camera_orientation_default。
# 0:向前,USB 端口在右侧
# 1:朝下,USB 接口在右侧
默认摄像机方向 = 0
  • 这些参数也可以作为输入参数从命令行中传递。现在运行主脚本:

# 对于串行连接:设置 udev.rules,以获得可用的 USB;允许串行权限
苏都 chmod 666 /dev/ttyUSB0

# 当一切正常,所有默认设置都已设置完毕:
python3 t265_to_mavlink.py

提示

查看所有可用的输入参数: python3 t265_to_mavlink.py --帮助

测试前的验证

  • 要验证 ArduPilot 是否接收到 视觉位置估计 信息,在Mission Planner地面站上:按 Ctrl+F 并单击 "Mavlink 检查器",您就能看到输入的数据。置信度可在信息 视觉位置实地 信心.

./_images/ros-vio-check-data.png
  • 跟踪置信度值的变化也可以通过Mission Planner地面站的信息面板、HUD 和语音进行通知。这些通知会在系统启动和置信度变为新状态时弹出,例如从 中型.

    • 在Mission Planner地面站中启用语音:选项卡 Config/Tuning > Planner > Speech > 勾选 "启用语音"。

    • 如果 HUD 上不断显示一些信息,您可能无法看到或听到信心级别通知。

    • 如果遥测速度较慢,通知可能会中断。您仍可在 MAVLink Inspector 中查看最新信息,信息包括 说明文本.

    • 如果遥测速度很慢,可能会被 VISION_POSITION_ESTIMATE 信息淹没。您可以通过设置 VISION_POSITION_ESTIMATE 中的第 10 位来禁用报文转发。 SERIALx_OPTIONS.请注意,在 GCS 中您将不再收到 VISION_POSITION_ESTIMATE。

地面测试

  • 开机后,ssh 进入配套电脑,导航到脚本并运行: python3 t265_to_mavlink.py.

  • 等待四旋翼飞行器图标出现在Mission Planner地面站的地图上。

  • 拿起载具四处走动,检查载具的位置移动是否显示在地图上。地图上的载具轨迹应反映真实的运动轨迹,不能有太多的失真或偏移。以下是在 2 米 x 2 米的正方形中行走的示例。

./_images/ros-vio-ground-test.png
  • 在测试过程中,查看置信度并验证跟踪性能。对于大多数应用来说,只有在以下情况下才应该信任全部 6dof 姿态 置信度。如果只需要旋转(3dof),则可以使用置信度较低的姿势。

  • 如果外部导航数据因任何原因丢失(跟踪丢失、脚本中断等),请重启(飞行)控制器。

提示

如果您在狭窄的环境中飞行,最好绕过飞行安全区,在地图上查看飞行轨迹,然后记住不要在安全区之外飞行/设置任务。

飞行测试

第一次飞行

  • 在稳定或 Alt 保持状态下起飞,检查载具是否稳定。

  • 移动载具并观察Mission Planner地面站上的位置,看跟踪是否稳定。

  • 切换到 Loiter,但随时准备在出现意外时切换回 Stabilize/Alt-Hold。

  • 否则,载具应能稳定地悬停并保持其位置。

  • 以不同的速度移动载具(平移、旋转),随时准备切换回稳定/备用状态。

如果一切正常,下次就可以在 Loiter 模式下上膛和起飞。

提示

在切换到 "闲置 "模式之前,请务必确认位置反馈运行正常。还要注意环境中的安全边界,即由于缺乏功能、快速或旋转运动而可能失去跟踪功能的地方。

室内外实验

数据闪存记录

  • 目视里程信息将显示在 面孔 数据闪存日志信息。

  • EKF 的目视里程测量信息将显示在 XKFD 信息中

启动时自动运行

脚本可在启动时自动运行。

  • 下载或创建 shell 文件 t265.sh,修改路径为 t265_to_mavlink.py 脚本,然后使其可执行:

wget https://raw.githubusercontent.com/thien94/vision_to_mavros/master/scripts/t265.sh 纳米 t265.sh

# 在 t265.sh 中,以我为例,将路径改为 t265_to_mavlink.py:
# /home/ubuntu/catkin_ws/src/vision_to_mavros/scripts/t265_to_mavlink.py

chmod +x /path/to/t265.sh

# 运行测试 shell。脚本 t265_to_mavlink.py 应正常运行
./t265.sh
  • 取决于您的系统,使用 任何方法 使脚本在启动时自动运行。在下面的步骤中,我们将使用 systemd 将其转化为一种服务。

  • 让我们创建一个文件 /etc/systemd/system/t265.service 内容如下。之后设置您的实际用户名 用户= 并设置正确的 t265.shExecStart=.

[单位]
说明=真实 T265 服务
之后=多用户目标
启动限制间隔秒=0
冲突=

[服务]
用户=乌托邦
环境文件=
ExecStartPre=
执行启动=/home/ubuntu/catkin_ws/src/vision_too_mavros/scripts/t265.sh

重新启动=失灵
重启安全=1

[安装]
想要=多用户目标
  • 就是这样。现在我们可以启动服务,让它在开机时自动启动:

systemctl 启动 t265 systemctl 以便 t265