Skip to content

Offboard控制

WARNING

Offboard control is dangerous. 这是通过 Mavlink 协议完成的, 特别是 SET_POSITION_TARGET_LOCAL_NEDSET_ATTITUDE_TARGET 消息。

Offboard控制背后的想法是能够使用在自动驾驶仪外运行的软件来控制 PX4 飞控。 This is done through the MAVLink protocol, specifically the SET_POSITION_TARGET_LOCAL_NED and the SET_ATTITUDE_TARGET messages.

Offboard控制固件设置

在进行Offboard开发前,您需要在固件端做两个设置。

Enable RC Override

In QGroundControl you can set the COM_RC_OVERRIDE parameter to automatically switch from offboard mode (or any mode) to Position mode if the RC sticks are moved. This is the best way to ensure that an operator can easily take control of the vehicle and switch to the safest flight mode.

1. 将遥控开关映射到离板模式激活

In QGroundControl you can set the RC_MAP_OFFB_SW parameter to the RC channel that will be used to activate offboard mode. This can be used to switch between offboard mode and the mode set by the mode switch (RC_MAP_MODE_SW). You can also switch into offboard mode using a GCS/MAVLink so this is not "mandatory".

Note also that this mechanism is not as "safe" as using RC Override to switch out of offboard mode, because the mode you switch to is unpredictable.

2. 启用机载计算机接口

Enable MAVLink on the serial port that you connect to the companion computer (see Companion Computers).

硬件设置

通常,有三种方式设置Offboard模式通信。

串口电台

  1. 一端连接飞控的 UART

  2. 一端连接地面站电脑

    参考电台包括:

Mermaid graph: mavlink channel

板载处理器

在飞行器上部署一台小型将计算机,用 UART 转 USB 适配器连接飞控。 这里有许多可能性,这将取决于您除了向自驾仪发送指令外,还想要做什么样的额外机载处理。 Some examples are provided in Companion Computers.

Mermaid diagram: Companion mavlink

部署在飞行器上的小型计算机除了通过 UART - USB 适配器连接到自动驾驶仪外,同时还可通过WiFi连接至运行 ROS 的地面站。 这可以是上述配备了WiFi适配器的任一计算机。

Mermaid graph: ROS