오프보드(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) 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.
INFO
- 이 모드에는 위치 또는 자세/태도 정보(GPS, 광학 흐름, 시각-관성 주행 거리 측정, 모캡 등)가 필요합니다.
- 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. - 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 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 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.
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
WARNING
The following list shows the OffboardControlMode
options for copter, fixed-wing, and VTOL. For rovers see the rover section.
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 | thrust_and_torque field | direct_actuator field | required estimate | required message |
---|---|---|---|---|---|---|---|---|---|
position (NED) | ✓ | - | - | - | - | - | - | position | TrajectorySetpoint |
velocity (NED) | ✗ | ✓ | - | - | - | - | - | velocity | TrajectorySetpoint |
acceleration (NED) | ✗ | ✗ | ✓ | - | - | - | - | velocity | TrajectorySetpoint |
attitude (FRD) | ✗ | ✗ | ✗ | ✓ | - | - | - | none | VehicleAttitudeSetpoint |
body_rate (FRD) | ✗ | ✗ | ✗ | ✗ | ✓ | - | - | none | VehicleRatesSetpoint |
thrust and torque (FRD) | ✗ | ✗ | ✗ | ✗ | ✗ | ✓ | - | none | VehicleThrustSetpoint and 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.
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 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
The following input combination is supported:
- quaternion
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]
.
- quaternion
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
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]
.
탐사선
Rover modules must set the control mode using OffboardControlMode
and use the appropriate messages to configure the corresponding setpoints. The approach is similar to other vehicle types, but the allowed control mode combinations and setpoints are different:
Category | 사용법 | Setpoints |
---|---|---|
(Recommended) Rover Setpoints | General rover control | RoverPositionSetpoint, RoverSpeedSetpoint, RoverAttitudeSetpoint, RoverRateSetpoint, RoverThrottleSetpoint, RoverSteeringSetpoint |
Actuator Setpoints | Direct actuator control | ActuatorMotors, ActuatorServos |
(Deprecated) Trajectory Setpoint | General vehicle control | TrajectorySetpoint |
Rover Setpoints
The rover modules use a hierarchical structure to propagate setpoints:
The "highest" setpoint that is provided will be used within the PX4 rover modules to generate the setpoints that are below it (overriding them!). With this hierarchy there are clear rules for providing a valid control input:
- Provide a position setpoint or
- One of the setpoints on the "left" (speed or throttle) and one of the setpoints on the "right" (attitude, rate or steering). All combinations of "left" and "right" setpoints are valid.
The following are all valid setpoint combinations and their respective control flags that must be set through OffboardControlMode (set all others to false). Additionally, for some combinations we require certain setpoints to be published with NAN
values so that the setpoints of interest are not overridden by the rover module (due to the hierarchy above). ✓ are the relevant setpoints we publish, and ✗ are the setpoint that need to be published with NAN
values.
Setpoint Combination | Control Flag | RoverPositionSetpoint | RoverSpeedSetpoint | RoverThrottleSetpoint | RoverAttitudeSetpoint | RoverRateSetpoint | RoverSteeringSetpoint |
---|---|---|---|---|---|---|---|
Position | position | ✓ | |||||
Speed + Attitude | velocity | ✓ | ✓ | ||||
Speed + Rate | velocity | ✓ | ✗ | ✓ | |||
Speed + Steering | velocity | ✓ | ✗ | ✗ | ✓ | ||
Throttle + Attitude | attitude | ✓ | ✓ | ||||
Throttle + Rate | body_rate | ✓ | ✓ | ||||
Throttle + Steering | thrust_and_torque | ✓ | ✓ |
INFO
If you intend to use the rover setpoints, we recommend using the PX4 ROS 2 Interface Library instead since it simplifies the publishing of these setpoints.
Actuator Setpoints
Instead of controlling the vehicle using position, speed, rate and other setpoints, you can directly control the motors and actuators using ActuatorMotors and ActuatorServos. In OffboardControlMode set direct_actuator
to true and all other flags to false.
INFO
This bypasses the rover modules including any limits on steering rates or accelerations and the inverse kinematics step. We recommend using RoverSteeringSetpoint and RoverThrottleSetpoint instead for low level control (see Rover Setpoints).
(Deprecated) Trajectory Setpoint
WARNING
The Rover Setpoints are a replacement for the TrajectorySetpoint and we highly recommend using those instead as they have a well defined behaviour and offer more flexibility.
The rover modules support the position, velocity and yaw fields of the TrajectorySetpoint. However, only one of the fields is active at a time and is defined by the flags of OffboardControlMode:
Control Mode Flag | Active Trajectory Setpoint Field |
---|---|
position | position |
velocity | velocity |
attitude | yaw |
INFO
Ackermann rovers do not support the yaw setpoint.
Generic Vehicle
The following offboard control modes bypass all internal PX4 control loops and should be used with great care.
px4_msgs::msg::VehicleThrustSetpoint + px4_msgs::msg::VehicleTorqueSetpoint
- The following input combination is supported:
xyz
for thrust andxyz
for torque.
- All the values are in the drone body FRD frame and normalized in [-1, 1].
- The following input combination is supported:
px4_msgs::msg::ActuatorMotors + px4_msgs::msg::ActuatorServos
- You directly control the motor outputs and/or servo outputs.
- Currently works at lower level than then
control_allocator
module. Do not publish these messages when not in offboard mode. - All the values normalized in
[-1, 1]
. For outputs that do not support negative values, negative entries map toNaN
. NaN
maps to disarmed.
MAVLink Messages
The following MAVLink messages and their particular fields and field values are allowed for the specified vehicle frames.
멀티콥터/VTOL
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).
- Position setpoint (only
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).
- The following input combinations are 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.- 다음 입력 조합이 지원됩니다.
- 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
).
- Attitude/orientation (
- 다음 입력 조합이 지원됩니다.
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.
- Specify the type of the setpoint in
- Position setpoint (
- The following input combinations are supported (via
:::
값들은 다음과 같습니다:
- 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 : Loiter 설정점 (설정점을 중심으로 선회 비행합니다).
- 16384 : 유휴 설정점 (제로 스로틀, 제로 롤/피치).
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.
- Position setpoint (only
- The following input combinations are supported (via
:::
값들은 다음과 같습니다:
- 4096 : 이륙 설정점.
- 8192: 착륙 설정점.
- 12288 : Loiter 설정점 (설정점을 중심으로 선회 비행합니다).
- 16384 : 유휴 설정점 (제로 스로틀, 제로 롤/피치).
PX4 supports the following
coordinate_frame
values (only): MAV_FRAME_GLOBAL.- 다음 입력 조합이 지원됩니다.
- 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
).
- Attitude/orientation (
- 다음 입력 조합이 지원됩니다.
탐사선
Rover does not support a MAVLink offboard API (ROS2 is supported).
오프보드 매개변수
Offboard mode is affected by the following parameters:
매개변수 | 설명 |
---|---|
COM_OF_LOSS_T | Time-out (in seconds) to wait when offboard connection is lost before triggering offboard lost failsafe (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 | 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 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).
The following resources may be useful for a developer audience: