# Offboard 模式
The vehicle obeys position, velocity, acceleration, attitude, attitude rates or thrust/torque setpoints provided by some source that is external to the flight stack, such as a companion computer. The setpoints may be provided using MAVLink (or a MAVLink API such as MAVSDK (opens new window)) 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 enables offboard control only after receiving the signal for more than a second, and will regain control if the signal stops.
注解
- 此模式需要位置或位/姿信息 - 例如 GPS、光流、视觉惯性里程计、mocap 等。
- 除了更改模式外, 禁止遥控器控制。
- 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. - Not all coordinate frames and field values allowed by MAVLink are supported for all setpoint messages and vehicles. 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 parameters COM_OBL_ACT and 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. 像上传、下载任务这样的操作可以在任何模式下执行。
# ROS 2 Messages
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:
- Controls the level of the PX4 control architecture at which offboard setpoints must be injected, and disables the bypassed controllers.
- Determines which valid estimates (position or velocity) are required, and also which setpoint messages should be used.
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.
desired control quantity | position field | velocity field | acceleration field | attitude field | body_rate field | actuator field | required estimate | required message |
---|---|---|---|---|---|---|---|---|
position (NED) | ✓ | - | - | - | - | - | position | TrajectorySetpoint |
velocity (NED) | ✗ | ✓ | - | - | - | - | velocity | TrajectorySetpoint |
acceleration (NED) | ✗ | ✗ | ✓ | - | - | - | velocity | TrajectorySetpoint |
attitude (RFD) | ✗ | ✗ | ✗ | ✓ | - | - | none | VehicleAttitudeSetpoint |
body_rate (RFD) | ✗ | ✗ | ✗ | ✗ | ✓ | - | none | VehicleRatesSetpoint |
thrust and torque (RFD) | ✗ | ✗ | ✗ | ✗ | ✗ | ✓ | none | VehicleThrustSetpoint and VehicleTorqueSetpoint |
where ✓ means that the bit is set, ✗ means that the bit is not set and -
means that the bit is value is irrelevant.
# Copter
px4_msgs::msg::TrajectorySetpoint (opens new window)
- 支持以下输入组合:
- Position setpoint (
position
different fromNaN
). Non-NaN
values of velocity and acceleration are used as feedforward terms for the inner loop controllers. - Velocity setpoint (
velocity
different fromNaN
andposition
set toNaN
). Non-NaN
values acceleration are used as feedforward terms for the inner loop controllers. - Acceleration setpoint (
acceleration
different fromNaN
andposition
andvelocity
set toNaN
)
- Position setpoint (
- All values are interpreted in NED (Nord, East, Down) coordinate system and the units are [m], [m/s] and [m/s^2] for position, velocity and acceleration, respectively.
- 支持以下输入组合:
px4_msgs::msg::VehicleAttitudeSetpoint (opens new window)
- The following input combination is supported:
- quaterion
q_d
+ thrust setpointthrust_body
. Non-NaN
values ofyaw_sp_move_rate
are used as feedforward terms expressed in Earth frame and in [rad/s].
- quaterion
- The quaterion represents the rotation between the drone body FRD (front, right, down) frame and the NED frame. The trust is in the drone body FRD frame and expressed in normalized [-1, 1] values.
- The following input combination is supported:
px4_msgs::msg::VehicleRatesSetpoint (opens new window)
- The following input combination is supported:
roll
,pitch
,yaw
andthrust_body
.
- All the value are in the drone body FRD frame. The rates are in [rad/s] while thrust_body is normalized in [-1, 1].
- The following input combination is supported:
px4_msgs::msg::VehicleThrustSetpoint (opens new window) + px4_msgs::msg::VehicleTorqueSetpoint (opens new window)
- The following input combination is supported:
xyz
for thrust andxyz
for torque.
- All the value are in the drone body FRD frame and normalized in [-1, 1].
- The following input combination is supported:
# MAVLink Messages
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)
- 支持以下输入组合:
- 位置设置值 (仅
x
,y
,z
) - Velocity setpoint (only
vx
,vy
,vz
) - 加速度设定值(仅
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 (opens new window) and MAV_FRAME_BODY_NED (opens new window).
- PX4 supports the following
- 支持以下输入组合:
SET_POSITION_TARGET_GLOBAL_INT (opens new window)
- 支持以下输入组合:
位置设定值(仅
lat_int
,lon_int
,alt
)Velocity setpoint (only
vx
,vy
,vz
)Thrust setpoint (only
afx
,afy
,afz
)注解
- 支持以下输入组合:
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 支持以下
coordinate_frame
值(仅限): MAV_FRAME_GLOBAL (opens new window)。
- SET_ATTITUDE_TARGET (opens new window)
- 支持以下输入组合:
- 带有推力设定值(
SET_ATTITUDE_TARGET.thrust
)的姿态和方向(SET_ATTITUDE_TARGET.q
)。 - 带有推力设定值(
SET_ATTITUDE_TARGET.thrust
)的机身速率(SET_ATTITUDE_TARGET
.body_roll_rate
,.body_pitch_rate
,.body_yaw_rate
)。
- 带有推力设定值(
- 支持以下输入组合:
# 固定翼
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 支持坐标系指定 (
coordinate_frame
字段): MAV_FRAME_LOCAL_NED (opens new window) 和 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. :::
值为:
- 4096:起飞设定值。
- 8192:降落设定值。
- 12288:悬停设定值(以设定值为中心绕圈飞行)。
- 16384:空闲设定值(油门为0, 横滚 / 俯仰为0)。
PX4 支持以下
coordinate_frame
值(仅限): MAV_FRAME_GLOBAL (opens new window)。SET_ATTITUDE_TARGET (opens new window)
- 支持以下输入组合:
- 带有推力设定值(
SET_ATTITUDE_TARGET.thrust
)的姿态和方向(SET_ATTITUDE_TARGET.q
)。 - 带有推力设定值(
SET_ATTITUDE_TARGET.thrust
)的机身速率(SET_ATTITUDE_TARGET
.body_roll_rate
,.body_pitch_rate
,.body_yaw_rate
)。
- 带有推力设定值(
- 支持以下输入组合:
# 无人车
- 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 支持坐标系指定 (
coordinate_frame
字段): MAV_FRAME_LOCAL_NED (opens new window) 和 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). 值为:- 下面的比特位没有置位,是正常表现。
- 12288:悬停设定值(无人机足够接近设定值时会停止)。
- PX4 支持坐标系(
corrdinate_frame
字段):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 丢失的失效保护措施 (COM_OBL_ACT 和 COM_OBL_RC_ACT ) |
COM_OBL_ACT | Mode to switch to if offboard control is lost when not connected to RC (Values are - 0: Land, 1: Hold, 2: Return ). |
COM_OBL_RC_ACT | Mode to switch to if offboard control is lost while still connected to RC control (Values are - 0: Position, 1: Altitude, 2: Manual, 3: Return , 4: Land). |
COM_RC_OVERRIDE | 控制多旋翼(或者多旋翼模式下的 VOTL)的摇杆移动量来切换到 位置模式。 默认情况下未启用此功能。 |
COM_RC_STICK_OV | 导致发射机切换到 位置模式 的摇杆移动量(如果 COM_RC_OVERRIDE 已启用)。 |
COM_RCL_EXCEPT | Specify modes in which RC loss is ignored and the failsafe action not triggered. 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 (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).
以下资源可能对开发者有用: