# Offboard 模式
飞行器根据飞行控制栈外部(如机载计算机)提供的设定值控制位置、速度、加速度、姿态以及推力/力矩。 设置值可以经由 MAVLink 提供(也可以是一个类似 MAVSDK (opens new window)的MAVLink API)或者经由 ROS 2 提供。
PX4要求外部控制器提供2Hz连续的“有效存在”信号,该信号可由任意支持的 MAVLink 设置点消息或ROS 2 OffboardControlMode 消息提供。 PX4只有在收到该种信号超过1秒后才有效,如果该种信号停止飞行控制栈将重新获得控制权(脱离Offboard模式)。
注解
- 此模式需要位置或位/姿信息 - 例如 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).
- 飞行器必须已经收到一条 MAVLink 设置点消息或 ROS 2 OffboardControlMode 消息,才允许在Offboard模式下解锁或者在飞行中切换至Offboard模式。
- 如果没有以 > 2Hz 的速度收到MAVLink 设置点消息或
OffboardControlMode
,飞行器将退出Offboard模式。 - 并非所有 MAVLink 支持的坐标系和字段值都被设定值消息和飞行器支持。 Read the sections below carefully to ensure only supported values are used.
# 描述
Offboard mode is used for controlling vehicle movement and attitude, by setting position, velocity, acceleration, attitude, attitude rates or thrust/torque setpoints.
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. The stream must be sent for at least a second before PX4 will arm in offboard mode, or switch to offboard mode when flying. 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.
When using MAVLink the setpoint messages convey both the signal to indicate that the external source is "alive", and the setpoint value itself. In order to hold position in this case the vehicle must receive a stream of setpoints for the current position.
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.
Note that offboard mode only supports a very limited set of MAVLink commands and messages. Operations, like taking off, landing, return to launch, may be best handled using the appropriate modes. Operations like uploading, downloading missions can be performed in any mode.
# ROS 2 消息
The following ROS 2 messages and their particular fields and field values are allowed for the specified frames. In addition to providing heartbeat functionality, OffboardControlMode
has two other main purposes:
- 控制Offboard设定值在 PX4 控制架构 中的哪个等级上被注入执行,并禁止绕过控制器。
- 确定需要哪种有效地估计(位置或速度),以及应该使用哪种设定值消息。
The OffboardControlMode
message is defined as shown.
# Off-board control mode
uint64 timestamp # time since system start (microseconds)
bool position
bool velocity
bool acceleration
bool attitude
bool body_rate
bool 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. The first field that has a non-zero value (from top to bottom) defines what valid estimate is required in order to use offboard mode, and the setpoint message(s) that can be used. 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.
期望控制对象 | 位置 | 速度 | 加速度 | 姿态 | 体轴角速率 | 执行器字段 | direct_actuator field | 所需状态估计 | 所需消息 |
---|---|---|---|---|---|---|---|---|---|
位置 (NED) | ✓ | - | - | - | - | - | - | 位置 | TrajectorySetpoint |
速度 (NED) | ✗ | ✓ | - | - | - | - | - | 速度 | TrajectorySetpoint |
加速度(NED) | ✗ | ✗ | ✓ | - | - | - | - | 速度 | TrajectorySetpoint |
姿态(FRD) | ✗ | ✗ | ✗ | ✓ | - | - | - | 无 | VehicleAttitudeSetpoint |
体轴角速率 (FRD) | ✗ | ✗ | ✗ | ✗ | ✓ | - | - | 无 | VehicleRatesSetpoint |
推力和力矩(FRD) | ✗ | ✗ | ✗ | ✗ | ✗ | ✓ | - | 无 | VehicleThrustSetpoint 和 VehicleTorqueSetpoint |
direct motors and servos | ✗ | ✗ | ✗ | ✗ | ✗ | ✗ | ✓ | none | 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.
注解
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 (opens new window)
- 支持以下输入组合:
- 位置设定值(
position
不为NaN
)。 非-NaN
速度和加速度被用作内环控制律的前馈项。 - 速度设定值(
velocity
不为NaN
同时position
为NaN
). 非-NaN
加速度被用作内环控制律的前馈项。 - 加速度设定值(
acceleration
不为NaN
同时position
和velocity
为NaN
)。
- 位置设定值(
- 所有值都是基于NED(北, 东, 地)坐标系,位置、速度和加速的单位分别为[m], [m/s] 和[m/s^2] 。
- 支持以下输入组合:
px4_msgs::msg::VehicleAttitudeSetpoint (opens new window)
The following input combination is supported:
- 姿态四元数
q_d
+ 推力设定值thrust_body
。 非-NaN
值的yaw_sp_move_rate
被用作大地坐标系下的偏航角前馈使用,单位为[rad/s]。
- 姿态四元数
The quaternion represents the rotation between the drone body FRD (front, right, down) frame and the NED frame. The thrust is in the drone body FRD frame and expressed in normalized [-1, 1] values.
px4_msgs::msg::VehicleRatesSetpoint (opens new window)
The following input combination is supported:
roll
,pitch
,yaw
andthrust_body
.
All the values are in the drone body FRD frame. The rates are in [rad/s] while thrust_body is normalized in [-1, 1].
# Generic Vehicle
The following offboard control modes bypass all internal PX4 control loops and should be used with great care.
px4_msgs::msg::VehicleThrustSetpoint (opens new window) + px4_msgs::msg::VehicleTorqueSetpoint (opens new window)
- 支持以下输入组合:
xyz
用于推力和xyz
用于力矩。
- All the values are in the drone body FRD frame and normalized in [-1, 1].
- 支持以下输入组合:
px4_msgs::msg::ActuatorMotors (opens new window) + px4_msgs::msg::ActuatorServos (opens new window)
- You directly control the motor outputs and/or servo outputs.
- All the values normalized in [-1, 1]. For outputs that do not support negative values, negative entries map to
NaN
. NaN
maps to disarmed.
# MAVLink 消息
The following MAVLink messages and their particular fields and field values are allowed for the specified frames.
# 直升机/垂直起降
SET_POSITION_TARGET_LOCAL_NED (opens new window)
The following input combinations are supported:
- 位置设置值 (仅
x
,y
,z
) - 速度设定值(仅
vx
,yy
,vz
) - Acceleration setpoint (only
afx
,afy
,afz
) - 位置设定值和速度设定值(速度设定值和加速度设定值被作为前馈使用;被叠加到位置控制器的输出上,结果作为速度控制器的输入使用)。
- 位置设定值和速度设定值以及加速度(速度和加速度设定值用作前馈;速度设定值叠加至位置控制器输出,并将结果作为速度控制器的输入;加速度设定值被叠加至速度控制器的输出中,输出结果用于计算推力矢量)。
- 位置设置值 (仅
PX4 supports the following
coordinate_frame
values (only): MAV_FRAME_LOCAL_NED (opens new window) and MAV_FRAME_BODY_NED (opens new window).
SET_POSITION_TARGET_GLOBAL_INT (opens new window)
支持以下输入组合:
位置设定值(仅
lat_int
,lon_int
,alt
)速度设定值(仅
vx
,vy
,vz
)Thrust setpoint (only
afx
,afy
,afz
)注解
加速度设定值被用来生成归一化的推力设定值(即不支持加速度设定值)。 :::
位置设定值和速度设定值(速度设定值被作为前馈使用;被叠加到位置控制器的输出上,结果作为速度控制器的输入使用)。
PX4 supports the following
coordinate_frame
values (only): MAV_FRAME_GLOBAL (opens new window).
SET_ATTITUDE_TARGET (opens new window)
- 支持以下输入组合:
- 带有推力设定值(
SET_ATTITUDE_TARGET.thrust
)的姿态和方向(SET_ATTITUDE_TARGET.q
)。 - 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 (opens new window)
支持以下输入组合(通过
type_mask
):位置设定值(仅
x
,y
,z
;速度和加速度设定值被忽略)。Specify the type of the setpoint in
type_mask
(if these bits are not set the vehicle will fly in a flower-like pattern): :::note Some of the setpoint type values below are not part of the MAVLink standard for thetype_mask
field. :::值为:
- 292:滑动设定值。 这会将 TECS 配置为空速优先于高度,以便在没有推力时使无人机滑行(即控制俯仰以调节空速)。 这相当于设置
type_mask
为POSITION_TARGET_TYPEMASK_Z_IGNORE
,POSITION_TARGET_TYPEMASK_VZ_IGNORE
,POSITION_TARGET_TYPEMASK_AZ_IGNORE
。 - 4096:起飞设定值。
- 8192:降落设定值。
- 12288:悬停设定值(以设定值为中心绕圈飞行)。
- 16384:空闲设定值(油门为0, 横滚 / 俯仰为0)。
- 292:滑动设定值。 这会将 TECS 配置为空速优先于高度,以便在没有推力时使无人机滑行(即控制俯仰以调节空速)。 这相当于设置
PX4 supports the coordinate frames (
coordinate_frame
field): MAV_FRAME_LOCAL_NED (opens new window) and MAV_FRAME_BODY_NED (opens new window).
SET_POSITION_TARGET_GLOBAL_INT (opens new window)
支持以下输入组合(通过
type_mask
):位置设定值(仅
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):
- Specify the type of the setpoint in
注解
The setpoint type values below are not part of the MAVLink standard for the type_mask
field.
The values are:
- 4096:起飞设定值。
- 8192:降落设定值。
- 12288:悬停设定值(以设定值为中心绕圈飞行)。
- 16384:空闲设定值(油门为0, 横滚 / 俯仰为0)。
PX4 supports the following
coordinate_frame
values (only): MAV_FRAME_GLOBAL (opens new window).SET_ATTITUDE_TARGET (opens new window)
- 支持以下输入组合:
- 带有推力设定值(
SET_ATTITUDE_TARGET.thrust
)的姿态和方向(SET_ATTITUDE_TARGET.q
)。 - 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 (opens new window)
支持以下输入组合(在
type_mask
中):位置设置值 (仅
x
,y
,z
)- Specify the type of the setpoint in
type_mask
:
- Specify the type of the setpoint in
注解
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 (opens new window) and MAV_FRAME_BODY_NED (opens new window).SET_POSITION_TARGET_GLOBAL_INT (opens new window)
支持以下输入组合(在
type_mask
中):- 位置设定值(仅
lat_int
,lon_int
,alt
)
- 位置设定值(仅
Specify the type of the setpoint in
type_mask
(not part of the MAVLink standard). The values are:- 下面的比特位没有置位,是正常表现。
- 12288:悬停设定值(无人机足够接近设定值时会停止)。
PX4 supports the coordinate frames (
coordinate_frame
field): MAV_FRAME_GLOBAL (opens new window).
SET_ATTITUDE_TARGET (opens new window)
- 支持以下输入组合:
- 带有推力设定值(
SET_ATTITUDE_TARGET.thrust
)的姿态和方向(SET_ATTITUDE_TARGET.q
)。 :::note 实际仅使用/提取了偏航设置。
- 带有推力设定值(
- 支持以下输入组合:
# Offboard参数
Offboard mode is affected by the following parameters:
参数 | 描述 |
---|---|
COM_OF_LOSS_T | Offboard 连接超时时间(以秒为单位),超过该时间未检测到offboard连接后将触发 offboard 连接丢失的失效保护措施 ( COM_OBL_RC_ACT ) |
COM_OBL_RC_ACT | Flight mode to switch to if offboard control is lost (Values are - 0 : Position, 1 : Altitude, 2 : Manual, 3 : *Return, 4 : *Land*). |
COM_RC_OVERRIDE | Controls whether stick movement on a multicopter (or VTOL in MC mode) causes a mode change to Position mode. 默认情况下未启用此功能。 |
COM_RC_STICK_OV | The amount of stick movement that causes a transition to Position mode (if COM_RC_OVERRIDE is enabled). |
COM_RCL_EXCEPT | 该参数指定一种模式,在该模式下将忽略RC丢失及不会触发RC丢失的失效保护动作。 将位 2 置1将在Offboard模式下忽略RC丢失。 |
# 开发者资源
Typically developers do not directly work at the MAVLink layer, but instead use a robotics API like MAVSDK (opens new window) or ROS (opens new window) (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).
The following resources may be useful for a developer audience: