微空无人机视觉导航教程5-视觉导航设置与飞行实践(Ardupilot及PX4)

2025-06-11 23:19:59

微空科技无人机视觉导航教程系列包含:

飞行平台搭建

飞控基础设置(Ardupilot及PX4)

机载电脑环境配置(树莓派4B+T265)

树莓派镜像迁移使用

视觉导航设置与飞行实践(Ardupilot及PX4)

双目VIO算法实现与应用(树莓派5+D435i)

拓展应用案例

《视觉导航设置与飞行实践篇》以 微空科技 MVD35(T265版) 飞行平台为例,介绍视觉导航所需传感器设置、飞控数据监测、自主飞行设置与飞行实践。D435i 版设置可参考后续篇章《双目VIO算法实现与应用篇(树莓派5+D435i)》。MVD35 飞行平台支持 Ardupilot 和 PX4固件,不同固件使用地面站不同,且具体设置过程差异较大,本篇将分别进行介绍:前半部分介绍 Ardupilot,后半部分介绍 PX4。

MVD35 套件购买

微空科技官方淘宝店

Ardupilot 视觉导航设置与飞行实践

准备内容(Ardupilot)

1. 硬件准备

MVD35(T265版) 飞行平台(Ardupilot 固件)

6S1P 1500mah 高压版锂电池

USB A - C 数据线

电脑及网络条件(科学上网)

适宜飞行的环境

2. 软件准备

Mission Planner,官方下载链接:https://firmware.ardupilot.org/Tools/MissionPlanner/MissionPlanner-latest.msi (Ardupilot 地面站)

MobaXterm,官方下载链接:https://mobaxterm.mobatek.net/download-home-edition.html (远程终端工具)

3. 使用技巧

MobaXterm:鼠标右键为粘贴快捷键;Ctrl + C 结束进程,或在需要输入密码处取消需要输入密码的 sudo 指令

Mission Planner:Ctrl + F 打开高级功能界面,选择 MAVLink Inspector 查看 飞控发送到地面站的 mavlink 数据内容

设置飞控参数:Mission Planner -> 配置/调试 -> 全部参数表 -> 修改对应参数

重启无人机:方法一:硬件重启——飞控断电后重新上电;方法二:软件重启—— Mission Planner -> 初始设置 -> >> 必要硬件 -> 指南针 -> Reboot

飞控设置(Ardupilot)

1. 设置 TRS 遥数一体链路

TRS 遥控与数传链路已经在《飞控基础设置篇》1. 设置数传连接中设置完成

2. 验证 TRS 遥数一体链路数据

TRS 遥控与数传链路已经在《飞控基础设置篇》中测试通过

Mission Planner 设置遥测速率:Mission Planner -> 配置/调试 -> Planner -> 遥测速率 (根据使用需求和数传带宽决定,一般设置刷新频率为 4Hz)

查看 TRS 数传链路传输速率与信号质量:Mission Planner -> 链接统计… -> 弹出 链接统计 窗口查看数据

3. 设置 MTF-01P 光流测距一体传感器

设置 MTF-01P 串口(《飞行平台搭建篇》中,已连接到 UART4):全部参数表 -> SERIAL4

复制代码

SERIAL4_BAUD 115

SERIAL4_OPTIONS 1024

SERIAL4_PROTOCOL 2

设置光流类型:全部参数表 -> FLOW_TYPE

复制代码

FLOW_TYPE 5

设置测距仪类型:全部参数表 -> RNGFND1_TYPE

复制代码

RNGFND1_TYPE 10

设置测距仪量程(MTF-01P 测距范围:1cm ~ 1200cm):写入参数后重启,刷新参数表 -> RNGFND1

复制代码

RNGFND1_MAX_CM 1200

RNGFND1_MIN_CM 1

4. 验证 MTF-01P 光流测距一体传感器数据

Mission Planner -> 飞行数据 -> 状态

查找关于光流数据 opt_m_x、opt_m_y、opt_qua;测距仪数据 rangefinder1,移动无人机,观察数据变化是否正确

5. 设置 T265 视觉传感器

设置视觉传感器位置和类型(视觉传感器为 T265,安装位置为机架正前方距离中心 0.05m 处):全部参数表 -> VISO

复制代码

VISO_POS_X 0.05

VISO_POS_Y 0

VISO_POS_Z 0

VISO_TYPE 2

设置飞控时间同步来源(同步树莓派 mavlink 时间,以融合视觉传感器数据):全部参数表 -> BRD

复制代码

BRD_RTC_TYPES 2

设置地面站 SYSID (接受树莓派控制指令):全部参数表 -> SYSID

复制代码

SYSID_MYGCS 1

6. 验证 T265 视觉传感器

根据《机载电脑环境配置篇》10. 节点测试 验证各个节点并将启动脚本配置为 apm ,启动全部节点(T265, mavros, vision_to_mavros)

复制代码

roslaunch vision_to_mavros t265_all_nodes.launch

查看飞控收到的视觉传感器数据:Mission Planner -> Ctrl+F -> MAVLink Inspector -> Comp 240 MAV_COMP_ID_UDP_BRIDGE(树莓派发送的数据) -> VISION_POSITION_ESTIMATE(视觉传感器数据)

确认 VISION_POSITION_ESTIMATE 数据频率能达到 30Hz 左右,否则可能是数传传输带宽不足、信号不佳或丢包率过高所致;移动无人机,观察以无人机 NED 坐标系的位置数据变化是否正确

7. 设置飞控融合信号源

取消融合全部传感器数据:全部参数表 -> EK3 -> EK3_SRC_OPTIONS

复制代码

EK3_SRC_OPTIONS 0

第一信号源设置为 视觉传感器+测距仪 组合:全部参数表 -> EK3 -> EK3_SRC1

复制代码

EK3_SRC1_POSXY 6

EK3_SRC1_POSZ 2

EK3_SRC1_VELXY 6

EK3_SRC1_VELZ 6

EK3_SRC1_YAW 6

第二信号源设置为 光流传感器+测距仪+罗盘 组合:全部参数表 -> EK3 -> EK3_SRC2

复制代码

EK3_SRC2_POSXY 0

EK3_SRC2_POSZ 2

EK3_SRC2_VELXY 5

EK3_SRC2_VELZ 0

EK3_SRC2_YAW 1

设置信号源选择通道(根据具体遥控器通道设置,以 通道 6 为例):全部参数表 -> RC6

复制代码

RC6_OPTION 90

8. 验证信号源切换功能

验证信号源切换成功:Mission Planner -> 飞行数据 -> 消息

拨动信号源切换开关,选择第一或第二信号源,可以看到 消息 界面显示融合信号源情况,并在 Loiter 飞行模式下,满足进入该模式会显示 准备解锁 (图中未启动树莓派上节点,没有视觉数据,所以显示 Bad Vision Position 在第一信号源情况下 Loiter 飞行模式并不能解锁,切换到第二信号源,成功融合光流数据后,显示 准备解锁,可以解锁飞行,并进行定点悬停)

视觉定位与导航飞行实践(Ardupilot)

方式一:遥控器手动控制

通过使用视觉传感器,无人机可以在遥控器手动操作下进行定点悬停飞行,并在 Loiter 模式下进行简单便捷的控制与随时定点悬停

飞行准备:打开遥控器 -> 启动无人机 -> Mission Planner 连接 TRS 高频头 -> MobaXterm 连接树莓派

启动视觉传感器:MobaXterm 启动所有节点(T265, mavros, vision_to_mavros)

复制代码

roslaunch vision_to_mavros t265_all_nodes.launch

检查飞控状态:Mission Planner 上检查视觉传感器数据、所选信号源、飞行模式、是否可解锁、是否有报错信息等

启动飞行:Loiter 模式下起飞,或在 AltHold 模式下起飞后切换到 Loiter 模式,油门摇杆处于中点位置附近,其它摇杆回中时,无人机能够保持稳定的定点悬停飞行

飞行监测:启动视觉传感器后,可通过树莓派上 rviz 机器人可视化程序实时查看无人机姿态、位置、轨迹等信息(rviz 操作可参考《机载电脑环境配置篇》11. 姿态轨迹可视化);飞行结束后,可通过 Mission Planner 下载日志进行分析

方式二:Mission Planner 交互式控制

通过视觉传感器的定位,可以在 Mission Planner 上直接控制无人机,配合树莓派 rviz 机器人可视化程序与 Mission Planner 地图显示无人机方向位置等信息,进行实时的监测,同时在 Mission Planner 地图上可以进行交互式控制,控制无人机飞行位置等

飞行准备:打开遥控器 -> 启动无人机 -> Mission Planner 连接 TRS 高频头 -> MobaXterm 连接树莓派

启动视觉传感器:MobaXterm 启动所有节点(T265, mavros, vision_to_mavros)

复制代码

roslaunch vision_to_mavros t265_all_nodes.launch

检查飞控状态:Mission Planner 上检查视觉传感器数据、所选信号源、飞行模式、是否可解锁、是否有报错信息等

设置 EKF 原点:Mission Planner -> 右键点击地图界面,呼出选项列表 -> 设置家在此 -> Set EKF Origin Here (设置后,在地图上会显示无人机图标表示无人机方向与位置信息)

放大地图:将无人机图标所在区域放大到最大倍率,可以更明显观察无人机的位置方向信息的变化)

确定安全边界:启动 rviz 辅助监测(rviz 操作可参考《机载电脑环境配置篇》11. 姿态轨迹可视化);拿起无人机围绕飞行空间移动, rviz 实时显示位置及轨迹,Mission Planner 上地图显示飞机的轨迹,了解现实环境中的位置与地图上位置的对应关系与比例,便于安全飞行(注意:此处需要科学上网,Mission Planner 使用谷歌地图!Mission Planner 使用谷歌地图!Mission Planner 使用谷歌地图!)

解锁:Mission Planner -> 飞行数据 -> 动作 -> 解锁/锁定(无人机将会解锁,桨叶缓慢转动)

起飞:Mission Planner -> 右键点击地图界面,呼出选项列表 -> TakeOff -> 弹窗输入起飞高度 1 单位:米(无人机将会缓慢起飞至指定高度后定点悬停待命)

地图选点飞行:Mission Planner -> 右键点击地图想要飞往的位置,呼出选项列表 -> 飞行至此(无人机进入 Guided 模式,将会转向并飞向指定位置后定点悬停待命,飞行途中或达到指定位置定点悬停后,可重复使用选点飞行,实时交互控制飞行)

降落:Mission Planner -> 飞行数据 -> 动作 -> 选择 Land 模式 -> 设置模式(无人机将会缓慢降落,降落后电机进入怠速状态,15 秒无电机输出操作将会自动上锁)

方式三:ROS 脚本自主控制

通过树莓派上 python 脚本,可以控制无人机进行自主飞行,完成一些预设或智能化的任务。树莓派上文件目录 ~/vision_ws/src/vision_to_mavros/scripts 下包含了脚本控制自主飞行的范例:

mavros_control1.py 脚本执行无人机起飞至 1.2m 高度,保持该高度并以边长为 0.4m 的正方形轨迹进行移动,飞行一圈回到原点后降落;

mavros_control2.py 脚本执行无人机起飞至 1m 高度,保持该高度并以起点为圆心,半径为 1m 的圆形轨迹进行移动,飞行两圈后回到圆心并降落。

飞行准备:打开遥控器 -> 启动无人机 -> Mission Planner 连接 TRS 高频头 -> MobaXterm 连接树莓派

启动视觉传感器:MobaXterm 启动所有节点(T265, mavros, vision_to_mavros)

复制代码

roslaunch vision_to_mavros t265_all_nodes.launch

检查飞控状态:Mission Planner 上检查视觉传感器数据、所选信号源、飞行模式、是否可解锁、是否有报错信息等

设置 EKF 原点

方法一:地面站设置 EKF 原点:Mission Planner -> 右键点击地图界面,呼出选项列表 -> 设置家在此 -> Set EKF Origin Here (设置后,在地图上会显示无人机图标表示无人机方向与位置信息)

方法二:树莓派脚本设置 EKF 原点(需安装《机载电脑环境配置篇》中选装的 Pymavlink)

复制代码

rosrun vision_to_mavros set_origin.py

执行脚本:脚本文件可自行编写或根据需求修改,执行范例 mavros_control2 如下

复制代码

rosrun vision_to_mavros mavros_control2.py

飞行监测:启动视觉传感器后,可通过树莓派上 rviz 机器人可视化程序实时查看无人机姿态、位置、轨迹等信息(rviz 操作可参考《机载电脑环境配置篇》11. 姿态轨迹可视化);飞行结束后,可通过 Mission Planner 下载日志进行分析

Ardupilot 视觉导航设置与飞行实践实测完成,D435i 版设置可参考后续篇章《双目VIO算法实现与应用篇(树莓派5+D435i)》,更多拓展应用请参考微空科技无人机视觉导航教程系列《拓展应用案例篇》

PX4 视觉导航设置与飞行实践

准备内容(PX4)

1.硬件准备

MVD35(T265版) 飞行平台(PX4 固件)

6S1P 1500mah 高压版锂电池

USB A - C 数据线

电脑及网络条件(无需科学上网)

适宜飞行的环境

2.软件准备

QGroundControl,官方下载链接:https://d176tv9ibo4jno.cloudfront.net/latest/QGroundControl-installer.exe (PX4 地面站)

MobaXterm,官方下载链接:https://mobaxterm.mobatek.net/download-home-edition.html (远程终端工具)

3.使用技巧

MobaXterm:鼠标右键为粘贴快捷键;Ctrl + C 结束进程,或在需要输入密码处取消需要输入密码的 sudo 指令

修改参数:QGroundControl -> Vehicle Setup -> 参数 -> 找到并修改对应参数

独立窗口显示 MAVLink 检测 页面:QGroundControl -> Analyze Tools -> MAVLink 检测 -> 右上角独立窗口显示图标

主界面添加显示自定义观测数据:点击主界面下侧快捷数据窗口 -> 进入编辑并添加对应观测主题数据

重启无人机:方法一:硬件重启——飞控断电后重新上电;方法二:软件重启—— QGroundControl -> Vehicle Setup -> 参数 -> 工具 -> 重启飞行器

无线连接时,重启无人机后需要手动连接:QGroundControl -> Application Settings -> 通讯连接 -> TRS -> 连接

飞控设置(PX4)

1.设置 TRS 遥数一体链路

TRS 遥控与数传链路已经在《飞控基础设置篇》1.设置数传连接中设置完成

2.验证 TRS 遥数一体链路数据

TRS 遥控与数传链路已经在《飞控基础设置篇》中测试通过

按照《飞控基础设置篇》中连接方式,将无人机连接到地面站:QGroundControl -> Application Settings -> 通讯连接 -> TRS -> 连接

查看 TRS 数传链路传输速率与信号质量:QGroundControl -> Application Settings -> MAVLink -> MAVLink 链接状态(当前飞机)

3.设置 MTF-01P 光流测距一体传感器

本教程仅使用 MTF-01P 光流测距一体传感器中的测距仪部分,启用光流融合视觉传感器可参考微空科技无人机视觉导航教程系列《拓展应用案例篇》

设置 MTF-01P 端口(《飞行平台搭建篇》中,已连接到 UART4):Vehicle Setup -> 参数

复制代码

MAV_1_CONFIG TELEM3

MAV_1_MODE Normal

SER_TEL3_BAUD 115200 8N1

设置测距仪参数

复制代码

EKF2_MIN_RNG 0.02

EKF2_RNG_NOISE 0.03

设置高度估计融合测距仪,关闭气压计融合

复制代码

EKF2_RNG_CTRL Enabled

EKF2_BARO_CTRL Disabled

EKF2_HGT_REF Range sensor

重启生效(设置过程中,部分关联参数需要保存并重启后,才能继续设置次级参数)

4.验证 MTF-01P 光流测距一体传感器数据

QGroundControl -> Analyze Tools -> MAVLink 检测 -> DISTANCE_SENSOR -> current_distance

垂直方向移动无人机,观察数据变化是否正确(单位:厘米)

QGroundControl -> Analyze Tools -> MAVLink 检测 -> LOCAL_POSITION_NED -> z

垂直方向移动无人机,观察数据变化是否正确

z 数据应为负数(单位:米),且近似 DISTANCE_SENSOR -> current_distance 的负值,则表示当前高度仅融合测距仪数据

5.设置 T265 视觉传感器

设置视觉传感器位置(视觉传感器为 T265,安装位置为机架正前方距离中心 0.05m 处):Vehicle Setup -> 参数

复制代码

EKF2_EV_POS_X 0.05

设置视觉传感器融合数据(水平位置及航向),航向数据采用视觉传感器,关闭磁力计融合:Vehicle Setup -> 参数

复制代码

EKF2_EV_CTRL 9

EKF2_EV_DELAY 10

EKF2_EVP_NOISE 0.03

EKF2_EV_NOISE_MD EV noise parameters

EKF2_MAG_TYPE None

SYS_HAS_MAG 0

6.验证 T265 视觉传感器

根据《机载电脑环境配置篇》10. 节点测试 验证各个节点并将启动脚本配置为 px4 ,启动全部节点(T265, mavros, vision_to_mavros)

复制代码

roslaunch vision_to_mavros t265_all_nodes.launch

查看飞控收到的视觉传感器数据:QGroundControl -> Analyze Tools -> MAVLink 检测 -> Comp 240 -> VISION_POSITION_ESTIMATE(视觉传感器数据)

确认 VISION_POSITION_ESTIMATE 数据频率能达到 30Hz 左右,否则可能是数传传输带宽不足、信号不佳或丢包率过高所致;移动无人机,观察对应位置数据变化是否正确

QGroundControl -> Analyze Tools -> MAVLink 检测 -> Comp 1 -> LOCAL_POSITION_NED

查看 LOCAL_POSITION_NED 数据,x,y 应融合视觉传感器数据,z 应融合测距仪数据,移动无人机,观察数据表现是否与实际一致

视觉定位与导航飞行实践(PX4)

方式一: 遥控器手动控制

通过使用视觉传感器,无人机可以在遥控器手动操作下进行定点悬停飞行,并在 Position 模式下进行简单便捷的控制与随时定点悬停

飞行准备:打开遥控器 -> 启动无人机 -> QGroundControl 连接 TRS 高频头 -> MobaXterm 连接树莓派

启动视觉传感器:MobaXterm 启动所有节点(T265, mavros, vision_to_mavros)

复制代码

roslaunch vision_to_mavros t265_all_nodes.launch

检查飞控状态:QGroundControl 上检查测距仪、视觉传感器数据、飞行模式、电池电量、是否 Ready to Fly、及无人机信息等

启动飞行:Position 模式下起飞,或在 Altitude 模式下起飞后切换到 Position 模式,油门摇杆处于中点位置附近,其它摇杆回中时,无人机能够保持稳定的定点悬停飞行

飞行监测:启动视觉传感器后,可通过树莓派上 rviz 机器人可视化程序实时查看无人机姿态、位置、轨迹等信息(rviz 操作可参考 《机载电脑环境配置篇》11. 姿态轨迹可视化);飞行结束后,可通过 QGroundControl 下载日志(使用数传下载日志速度较慢,建议使用 USB 连接下载日志),并使用 PlotJuggler、Flight Review 等工具加载日志针对具体情况进行分析

方式二: ROS 脚本自主控制

通过树莓派上 python 脚本,可以控制无人机进行自主飞行,完成一些预设或智能化的任务。下面介绍创建脚本,完成基础控制的 demo 搭建流程。实现效果为:offb_sample1.py 脚本执行无人机起飞至 1m 高度,保持该高度并以边长为 0.5m 的正方形轨迹进行移动,飞行一圈回到原点后降落

无人机 offboard 模式参数设置

启动无人机,QGroundControl 连接 TRS 高频头

QGroundControl -> Vehicle Setup -> 参数

设置无人机 offboard 信号丢失响应:失去 offboard 控制信号 1s 后,无人机执行自动降落指令

复制代码

COM_OBL_RC_ACT Land mode

COM_OF_LOSS_T 1

修改 T265 坐标系转化对齐方式

MobaXterm 连接树莓派

修改 t265_tf_to_mavros.launch 文件

复制代码

sudo vim ~/vision_ws/src/vision_to_mavros/launch/t265_tf_to_mavros.launch

修改为

创建 Python 脚本 ROS 包

进入工作空间

复制代码

roscd

cd ..

cd src

创建新包(以 rospy 为依赖项)

复制代码

catkin_create_pkg px4_offboard_py rospy

构建新的软件包

复制代码

cd ..

catkin_make

验证并切换至脚本包目录

复制代码

roscd px4_offboard_py

创建脚本目录

复制代码

mkdir scripts

cd scripts

创建脚本

复制代码

touch offb_sample1.py

chmod +x offb_sample1.py

打开脚本并编辑代码

复制代码

sudo vim offb_sample1.py

复制代码

#!/usr/bin/env python

import rospy

import mavros

from geometry_msgs.msg import PoseStamped

from mavros_msgs.msg import State

from mavros_msgs.srv import CommandBool, SetMode

from geometry_msgs.msg import Point

current_state = State()

def state_callback(state):

global current_state

current_state = state

mavros.set_namespace()

des_pos = PoseStamped()

state_sub = rospy.Subscriber('mavros/state', State, callback = state_callback)

position_pub = rospy.Publisher('mavros/setpoint_position/local', PoseStamped, queue_size = 10)

arming_drone = rospy.ServiceProxy('/mavros/cmd/arming', CommandBool)

setting_mode = rospy.ServiceProxy('mavros/set_mode', SetMode)

def offb_control_sample():

print("Init Node: Offboard_node")

rospy.init_node('Offboard_node', anonymous=True)

prev_state = current_state

rate = rospy.Rate(20.0)

des_pos.pose.position.x = 0

des_pos.pose.position.y = 0

des_pos.pose.position.z = 1

# waiting for FCU connection

while(not rospy.is_shutdown() and not current_state.connected):

print("Waiting for FCU connection")

rate.sleep()

print("FCU connected")

# Sending a few points before start

for i in range(60):

if(rospy.is_shutdown()):

break

position_pub.publish(des_pos)

rate.sleep()

print("Switching to offboard Mode")

setting_mode(base_mode=0, custom_mode="OFFBOARD")

last_request = rospy.get_rostime()

while((rospy.get_rostime() - last_request) < rospy.Duration(2.0)):

position_pub.publish(des_pos)

rate.sleep()

print("Arming the drone on offboard Mode")

if current_state.mode == "OFFBOARD":

arming_drone(True)

print("Take off to Point 1")

last_request = rospy.get_rostime()

while((rospy.get_rostime() - last_request) < rospy.Duration(8.0)):

position_pub.publish(des_pos)

rate.sleep()

print("Fly to Point 2")

des_pos.pose.position.x = 0

des_pos.pose.position.y = 0.5

des_pos.pose.position.z = 1

last_request = rospy.get_rostime()

while((rospy.get_rostime() - last_request) < rospy.Duration(2.0)):

position_pub.publish(des_pos)

rate.sleep()

print("Fly to Point 3")

des_pos.pose.position.x = 0.5

des_pos.pose.position.y = 0.5

des_pos.pose.position.z = 1

last_request = rospy.get_rostime()

while((rospy.get_rostime() - last_request) < rospy.Duration(2.0)):

position_pub.publish(des_pos)

rate.sleep()

print("Fly to Point 4")

des_pos.pose.position.x = 0.5

des_pos.pose.position.y = 0

des_pos.pose.position.z = 1

last_request = rospy.get_rostime()

while((rospy.get_rostime() - last_request) < rospy.Duration(2.0)):

position_pub.publish(des_pos)

rate.sleep()

print("Fly back to Point 1")

des_pos.pose.position.x = 0

des_pos.pose.position.y = 0

des_pos.pose.position.z = 1

last_request = rospy.get_rostime()

while((rospy.get_rostime() - last_request) < rospy.Duration(3.0)):

position_pub.publish(des_pos)

rate.sleep()

print("Vehicle Landing")

print("Mission End")

if __name__ == '__main__':

try:

offb_control_sample()

except rospy.ROSInterruptException:

pass

飞行脚本测试

飞行准备:打开遥控器 -> 启动无人机 -> QGroundControl 连接 TRS 高频头 -> MobaXterm 连接树莓派

将无人机放置在空旷的启动场地中,启动视觉传感器:MobaXterm 启动所有节点(T265, mavros, vision_to_mavros)

复制代码

roslaunch vision_to_mavros t265_all_nodes.launch

检查 VISION_POSITION_ESTIMATE 及 LOCAL_POSITION_NED 数据:VISION_POSITION_ESTIMATE 为 T265 传回定位信息;LOCAL_POSITION_NED 为融合后位置信息,通常无人机上电初始化位置为原点,启动视觉传感器融合后,原点为启动视觉传感器位置,通过 QGroundControl -> Analyze Tools -> MAVLink 检测 确认数据正常

检查飞控状态:QGroundControl 上检查飞行模式、电池电量、是否 Ready to Fly、及无人机信息等

无人机切换至 Position 飞行模式,脚本执行过程中,可随时通过遥控器夺取无人机控制权,飞行异常时,请及时将飞行模式切换至 Altitude 或 Stabilized 飞行模式并手动控制(offboard 模式下遥控器摇杆控制无效,需先切换飞行模式以获取控制权后,摇杆控制才会生效)

启动 rviz 监测运动轨迹(rviz 操作可参考《机载电脑环境配置篇》11. 姿态轨迹可视化)

启动脚本

复制代码

rosrun px4_offboard_py offb_sample1.py

5s 后,无人机解锁并起飞至 1m 高度,保持该高度并以边长为 0.5m 的正方形轨迹进行移动,飞行一圈回到原点后降落

飞行结束后,可通过 QGroundControl 下载日志(使用数传下载日志速度较慢,建议使用 USB 连接下载日志),并使用 PlotJuggler、Flight Review 等工具加载日志针对具体情况进行分析

PX4 视觉导航设置与飞行实践实测完成,D435i 版设置可参考后续篇章《双目VIO算法实现与应用篇(树莓派5+D435i)》,更多拓展应用请参考微空科技无人机视觉导航教程系列《拓展应用案例篇》