Skip to content

Offboard 模式

飞行器根据飞行控制栈外部(如机载计算机)提供的设定值控制位置、速度、加速度、姿态以及推力/力矩。 The setpoints may be provided using MAVLink (or a MAVLink API such as MAVSDK) or by ROS 2.

PX4 requires that the external controller provides a continuous 2Hz "proof of life" signal, by streaming any of the supported MAVLink setpoint messages or the ROS 2 OffboardControlMode message. PX4只有在收到该种信号超过1秒后才有效,如果该种信号停止飞行控制栈将重新获得控制权(脱离Offboard模式)。

INFO

  • 此模式需要位置或位/姿信息 - 例如 GPS、光流、视觉惯性里程计、mocap 等。
  • RC control is disabled except to change modes (you can also fly without any manual controller at all by setting the parameter COM_RC_IN_MODE to 4: Stick input disabled).
  • The vehicle must be already be receiving a stream of MAVLink setpoint messages or ROS 2 OffboardControlMode messages before arming in offboard mode or switching to offboard mode when flying.
  • The vehicle will exit offboard mode if MAVLink setpoint messages or OffboardControlMode are not received at a rate of > 2Hz.
  • 并非所有 MAVLink 支持的坐标系和字段值都被设定值消息和飞行器支持。 Read the sections below carefully to ensure only supported values are used.

描述

Offboard模式通过设置位置、速度、加速、姿态、姿态角速率或力/扭矩设定值来控制飞行器的位置和姿态。

PX4 must receive a stream of MAVLink setpoint messages or the ROS 2 OffboardControlMode at 2 Hz as proof that the external controller is healthy. 该消息必须持续发送1秒以上PX4才能在Offboard模式下解锁或在飞行中切换至Offboard模式。 If the rate falls below 2Hz while under external control PX4 will switch out of offboard mode after a timeout (COM_OF_LOSS_T), and attempt to land or perform some other failsafe action. The action depends on whether or not RC control is available, and is defined in the parameter COM_OBL_RC_ACT.

当使用 MAVLink 时,设定值消息既传达了外部控制器"正常运行"的信号也传达了设定值本身。 Offboard模式下要保持位置,飞行器必须接收到一个包含当前位置设定值的消息指令。

When using ROS 2 the proof that the external source is alive is provided by a stream of OffboardControlMode messages, while the actual setpoint is provided by publishing to one of the setpoint uORB topics, such as TrajectorySetpoint. In order to hold position in this case the vehicle must receive a stream of OffboardControlMode but would only need the TrajectorySetpoint once.

请注意,Offboard模式只支持比较有限的 MAVLink 指令和消息。 其他操作如起飞、降落、返航,最好使用适当的模式来处理。 像上传、下载任务这样的操作可以在任何模式下执行。

ROS 2 消息

以下 ROS 2 消息及其特定字段和字段值在特定的框架下是允许的。 In addition to providing heartbeat functionality, OffboardControlMode has two other main purposes:

  1. Controls the level of the PX4 control architecture at which offboard setpoints must be injected, and disables the bypassed controllers.
  2. 确定需要哪种有效估计(位置或速度),以及应该使用哪种设定值消息。

The OffboardControlMode message is defined as shown.

sh
# Off-board control mode

uint64 timestamp		# time since system start (microseconds)

bool position
bool velocity
bool acceleration
bool attitude
bool body_rate
bool thrust_and_torque
bool direct_actuator

The fields are ordered in terms of priority such that position takes precedence over velocity and later fields, velocity takes precedence over acceleration, and so on. 第一个非零字段(从上到下) 定义了Offboard模式所需的有效估计以及可用的设定值消息。 For example, if the acceleration field is the first non-zero value, then PX4 requires a valid velocity estimate, and the setpoint must be specified using the TrajectorySetpoint message.

期望控制对象位置速度加速度姿态姿态角速率执行器字段直接给电机所需状态估计所需消息
位置 (NED)------位置TrajectorySetpoint
速度 (NED)-----速度TrajectorySetpoint
加速度(NED)----速度TrajectorySetpoint
姿态(FRD)---VehicleAttitudeSetpoint
体轴角速率 (FRD)--VehicleRatesSetpoint
推力和力矩(FRD)-VehicleThrustSetpoint and VehicleTorqueSetpoint
直接给电机和舵机ActuatorMotors and ActuatorServos

where ✓ means that the bit is set, ✘ means that the bit is not set and - means that the bit is value is irrelevant.

INFO

Before using offboard mode with ROS 2, please spend a few minutes understanding the different frame conventions that PX4 and ROS 2 use.

旋翼机

  • px4_msgs::msg::TrajectorySetpoint

    • 支持以下输入组合:

      • Position setpoint (position different from NaN). Non-NaN values of velocity and acceleration are used as feedforward terms for the inner loop controllers.
      • Velocity setpoint (velocity different from NaN and position set to NaN). Non-NaN values acceleration are used as feedforward terms for the inner loop controllers.
      • Acceleration setpoint (acceleration different from NaN and position and velocity set to NaN)
    • 所有值都是基于NED(北, 东, 地)坐标系,位置、速度和加速的单位分别为[m], [m/s] 和[m/s^2] 。

  • px4_msgs::msg::VehicleAttitudeSetpoint

    • 支持以下输入组合:

      • quaternion q_d + thrust setpoint thrust_body. Non-NaN values of yaw_sp_move_rate are used as feedforward terms expressed in Earth frame and in [rad/s].
    • 姿态四元数表示无人机机体坐标系FRD(前、右、下) 与NED坐标系之间的旋转。 这个推力是在无人机体轴FRD坐标系下,并归一化为 [-1, 1] 。

  • px4_msgs::msg::VehicleRatesSetpoint

    • 支持以下输入组合:

      • roll, pitch, yaw and thrust_body.
    • 所有值都表示在无人机体轴FRD坐标系下。 角速率(roll, pitch, yaw) 单位为[rad/s] ,thrust_body归一化为 [-1, 1]。

Generic Vehicle

下面的offboard控制模式会绕过所有PX4内部的控制环,应当非常谨慎地使用。

下面的 MAVLink 消息及其特定字段和字段值在特定的帧下是允许的。

直升机/垂直起降

  • SET_POSITION_TARGET_LOCAL_NED

    • The following input combinations are supported:

      • Position setpoint (only x, y, z)
      • Velocity setpoint (only vx, vy, vz)
      • Acceleration setpoint (only afx, afy, afz)
      • Position setpoint and velocity setpoint (the velocity setpoint is used as feedforward; it is added to the output of the position controller and the result is used as the input to the velocity controller).
      • Position setpoint and velocity setpoint and acceleration (the velocity and the acceleration setpoints are used as feedforwards; the velocity setpoint is added to the output of the position controller and the result is used as the input to the velocity controller; the acceleration setpoint is added to the output of the velocity controller and the result used to compute the thrust vector).
    • PX4 supports the following coordinate_frame values (only): MAV_FRAME_LOCAL_NED and MAV_FRAME_BODY_NED.

  • SET_POSITION_TARGET_GLOBAL_INT

    • The following input combinations are supported:

      • Position setpoint (only lat_int, lon_int, alt)

      • Velocity setpoint (only vx, vy, vz)

      • Thrust setpoint (only afx, afy, afz)

        INFO

        Acceleration setpoint values are mapped to create a normalized thrust setpoint (i.e. acceleration setpoints are not "properly" supported).

:::

- Position setpoint **and** velocity setpoint (the velocity setpoint is used as feedforward; it is added to the output of the position controller and the result is used as the input to the velocity controller).
  • PX4 supports the following coordinate_frame values (only): MAV_FRAME_GLOBAL.

  • SET_ATTITUDE_TARGET

    • 支持以下输入组合:
      • Attitude/orientation (SET_ATTITUDE_TARGET.q) with thrust setpoint (SET_ATTITUDE_TARGET.thrust).
      • Body rate (SET_ATTITUDE_TARGET .body_roll_rate ,.body_pitch_rate, .body_yaw_rate) with thrust setpoint (SET_ATTITUDE_TARGET.thrust).

Fixed-wing

  • SET_POSITION_TARGET_LOCAL_NED

    • The following input combinations are supported (via type_mask):

      • Position setpoint (x, y, z only; velocity and acceleration setpoints are ignored).

        • Specify the type of the setpoint in type_mask (if these bits are not set the vehicle will fly in a flower-like pattern):

          INFO

          Some of the setpoint type values below are not part of the MAVLink standard for the type_mask field.

:::

    值为:

    - 292:滑动设定值。
      这会将 TECS 配置为空速优先于高度,以便在没有推力时使无人机滑行(即控制俯仰以调节空速)。
      It is equivalent to setting `type_mask` as `POSITION_TARGET_TYPEMASK_Z_IGNORE`, `POSITION_TARGET_TYPEMASK_VZ_IGNORE`, `POSITION_TARGET_TYPEMASK_AZ_IGNORE`.
    - 4096:起飞设定值。
    - 8192:降落设定值。
    - 12288:悬停设定值(以设定值为中心绕圈飞行)。
    - 16384:空闲设定值(油门为0, 横滚 / 俯仰为0)。
  • PX4 supports the coordinate frames (coordinate_frame field): MAV_FRAME_LOCAL_NED and MAV_FRAME_BODY_NED.

  • SET_POSITION_TARGET_GLOBAL_INT

    • The following input combinations are supported (via type_mask):

      • Position setpoint (only lat_int, lon_int, alt)

        • Specify the type of the setpoint in type_mask (if these bits are not set the vehicle will fly in a flower-like pattern):

          INFO

          The setpoint type values below are not part of the MAVLink standard for the type_mask field.

:::

    值为:

    - 4096:起飞设定值。
    - 8192:降落设定值。
    - 12288:悬停设定值(以设定值为中心绕圈飞行)。
    - 16384:空闲设定值(油门为0, 横滚 / 俯仰为0)。
  • PX4 supports the following coordinate_frame values (only): MAV_FRAME_GLOBAL.

  • SET_ATTITUDE_TARGET

    • 支持以下输入组合:
      • Attitude/orientation (SET_ATTITUDE_TARGET.q) with thrust setpoint (SET_ATTITUDE_TARGET.thrust).
      • Body rate (SET_ATTITUDE_TARGET .body_roll_rate ,.body_pitch_rate, .body_yaw_rate) with thrust setpoint (SET_ATTITUDE_TARGET.thrust).

无人车

  • SET_POSITION_TARGET_LOCAL_NED

    • The following input combinations are supported (in type_mask):

      • Position setpoint (only x, y, z)

        • Specify the type of the setpoint in type_mask:

          INFO

          The setpoint type values below are not part of the MAVLink standard for the type_mask field. ::

          值为:

          • 12288:悬停设定值(无人机足够接近设定值时会停止)。
      • Velocity setpoint (only vx, vy, vz)

    • PX4 supports the coordinate frames (coordinate_frame field): MAV_FRAME_LOCAL_NED and MAV_FRAME_BODY_NED.

  • SET_POSITION_TARGET_GLOBAL_INT

    • The following input combinations are supported (in type_mask):

      • Position setpoint (only lat_int, lon_int, alt)
    • Specify the type of the setpoint in type_mask (not part of the MAVLink standard). 值为:

      • 下面的比特位没有置位,是正常表现。
      • 12288:悬停设定值(无人机足够接近设定值时会停止)。
    • PX4 supports the coordinate frames (coordinate_frame field): MAV_FRAME_GLOBAL.

  • SET_ATTITUDE_TARGET

    • 支持以下输入组合:
      • Attitude/orientation (SET_ATTITUDE_TARGET.q) with thrust setpoint (SET_ATTITUDE_TARGET.thrust).

        INFO

        Only the yaw setting is actually used/extracted.

:::

Offboard参数

Offboard mode is affected by the following parameters:

参数描述
COM_OF_LOSS_TTime-out (in seconds) to wait when offboard connection is lost before triggering offboard lost failsafe (COM_OBL_RC_ACT)
COM_OBL_RC_ACTFlight mode to switch to if offboard control is lost (Values are - 0: Position, 1: Altitude, 2: Manual, 3: *Return, 4: *Land*).
COM_RC_OVERRIDEControls whether stick movement on a multicopter (or VTOL in MC mode) causes a mode change to Position mode. 默认情况下未启用此功能。
COM_RC_STICK_OVThe amount of stick movement that causes a transition to Position mode (if COM_RC_OVERRIDE is enabled).
COM_RCL_EXCEPT该参数指定一种模式,在该模式下将忽略RC丢失及不会触发RC丢失的失效保护动作。 Set bit 2 to ignore RC loss in Offboard mode.

开发者资源

Typically developers do not directly work at the MAVLink layer, but instead use a robotics API like MAVSDK or ROS (these provide a developer friendly API, and take care of managing and maintaining connections, sending messages and monitoring responses - the minutiae of working with Offboard mode and MAVLink).

以下资源可能对开发者有用: