# PX4 飞行模式总览

飞行模式定义了自驾仪如何响应遥控输入,以及它如何在全自主飞行期间管理飞行器运动。

这些模式为用户(飞行员)提供不同类型/级别的自动驾驶辅助,包括从起飞和着陆等常见任务的自动化,到更容易重新获得水平飞行及将飞行器保持在固定路径或位置的机制,等等。

This topic provides an overview of the available the flight modes for different frame types: multicopter (MC), fixed-wing (FW), VTOL, rovers/boats.

提示

More detailed information about specific flight modes can be found in Flying > Flight Modes.

# 飞行模式切换

飞行员可以使用遥控上的开关或地面站来切换飞行模式(见 飞行模式配置)。

并非所有飞行器都可以使用所有飞行模式,并且某些模式在不同飞行器类型上表现不同。

一些飞行模式仅在飞行前和飞行中某些特定条件下起作用(如 GPS 锁定,空速传感器,某个轴的姿态感测)。 除非满足合适的条件,否则 PX4 不会允许切换到这些模式。

Last of all, in multicopter autonomous modes RC stick movement will change the vehicle to Position mode by default (unless handling a critical battery failsafe). Stick movement is ignored for autonomous fixed-wing flight.

# 自主和手动模式

Flight Modes are, generally speaking, either manual or autonomous. Manual modes are those where the user has control over vehicle movement via the RC control sticks (or joystick), while autonomous modes are fully controlled by the autopilot, and require no pilot/remote control input.

提示

某些手动模式可能具有自驾辅助机制,以便更容易获得或恢复受控飞行。 如当遥控摇杆居中时,大部分飞行模式将使飞行器水平。

手动模式可以进一步分为 “简单” 和 ”特技“ 模式。 In the easy modes, roll and pitch sticks set the vehicle angle, resulting in left-right and forward-back movement in the horizontal plane (respectively). 这将不仅可以使运动变得可预测,而且因为角度受控,飞行器无法翻转。 在特技模式中,RC 摇杆控制角度旋转的速率(绕相应轴)。 飞行器可以翻转,虽然机动性更强,但更难飞行。

固定翼:

多旋翼:

Rover/Boat:

注解

Only manual and mission modes are supported. YOu can switch to any other mode but the behaviour will be the same as for manual mode.

#

The icons below are used within the document:

图标 描述
手动模式 需要遥控
自动模式. 除非切换模式,否则 RC 控制被默认失能。
需要定位(如 GPS,VIO, 或其它定位系统)。
需要高度(如来自气压计、测距仪)。
飞行模式难度(简单到困难)

# 多旋翼

# Position Mode (MC)

Position mode is an easy-to-fly RC mode in which roll and pitch sticks control acceleration over ground in the vehicle's forward-back and left-right directions (similar to a car's accelerator pedal), and throttle controls speed of ascent-descent. When the sticks are released/centered the vehicle will actively brake, level, and be locked to a position in 3D space — compensating for wind and other forces.

提示

Position mode is the safest manual mode for new fliers. Unlike Altitude and Manual/Stabilized modes the vehicle will stop when the sticks are centered rather than continuously drifting without constant manual guidance.

MC Position Mode

# Altitude Mode (MC)

Altitude mode is a relatively easy-to-fly RC mode in which roll and pitch sticks control vehicle movement in the left-right and forward-back directions (relative to the "front" of the vehicle), yaw stick controls rate of rotation over the horizontal plane, and throttle controls speed of ascent-descent.

When the sticks are released/centered the vehicle will level and maintain the current altitude. If moving in the horizontal plane the vehicle will continue until any momentum is dissipated by wind resistance. If the wind blows the aircraft will drift in the direction of the wind.

提示

Attitude mode is the safest non-GPS manual mode for new fliers. It is just like Manual/Stabilized mode but additionally stabilizes the vehicle altitude when the sticks are released.

MC Altitude Mode

# Manual/Stabilized Mode (MC)

The Manual/Stabilized mode stabilizes the multicopter when the RC control sticks are centered. To manually move/fly the vehicle you move the sticks outside of the center.

注解

This multicopter mode is enabled if you set either Manual or Stabilized modes for an MC vehicle.

When under manual control the roll and pitch sticks control the angle of the vehicle (attitude), the yaw stick controls the rate of rotation above the horizontal plane, and the throttle controls altitude/speed.

As soon as you release the control sticks they will return to the center deadzone. The multicopter will level out and stop once the roll and pitch sticks are centered. The vehicle will then hover in place/maintain altitude - provided it is properly balanced, throttle is set appropriately, and no external forces are applied (e.g. wind). The craft will drift in the direction of any wind and you have to control the throttle to hold altitude.

MC Manual Flight

# Acro Mode (MC)

Acro mode is the RC mode for performing acrobatic maneuvers e.g. rolls and loops.

The roll, pitch and yaw sticks control the rate of angular rotation around the respective axes and throttle is passed directly to the output mixer. When sticks are centered the vehicle will stop rotating, but remain in its current orientation (on its side, inverted, or whatever) and moving according to its current momentum.

MC Manual Acrobatic Flight

# Orbit Mode (MC)

The Orbit mode allows you to command a multicopter (or VTOL in multicopter mode) to fly in a circle, yawing so that it always faces towards the center.

A GCS is required to enable the mode, and to set the center position and initial radius of the orbit. By default the vehicle will then perform a slow ongoing orbit around the center position (1m/s) in a clockwise direction. RC control is optional, and can be used to change the orbit altitude, radius, speed, and direction.

Orbit Mode - MC

# Hold Mode (MC)

Hold mode causes the multicopter to stop and hover at its current position and altitude (maintaining position against wind and other forces). The mode can be used to pause a mission or to help regain control of a vehicle in an emergency. It can be activated with a pre-programmed RC switch or the QGroundControl Pause button.

# Return Mode (MC)

Return mode causes the vehicle to fly a clear path to a safe location. The mode may be activated manually (via a pre-programmed RC switch) or automatically (i.e. in the event of a failsafe being triggered).

The return behaviour depends on parameter settings, and may follow a mission path and/or mission landing pattern (if defined). By default a mulitcopter will simply ascend to a safe height, fly to its home position, and then land.

# Mission Mode (MC)

Mission mode causes the vehicle to execute a predefined autonomous mission (flight plan) that has been uploaded to the flight controller. The mission is typically created and uploaded with a Ground Control Station (GCS) application.

提示

The PX4 GCS is called QGroundControl (opens new window). QGroundControl is the same application we use for configuring PX4.

# Takeoff Mode (MC)

Takeoff mode causes the multicopter to climb vertically to takeoff altitude and hover in position.

# Land Mode (MC)

Land mode causes the multicopter to land at the location at which the mode was engaged.

# Follow Me Mode (MC)

Follow Me mode causes a multicopter to autonomously follow and track a user providing their current position setpoint. Position setpoints might come from an Android phone/tablet running QGroundControl or from a MAVSDK app.

# Offboard Mode (MC)

Offboard mode causes the multicopter to obey a position, velocity or attitude setpoint provided over MAVLink.

注解

This mode is intended for vehicle control from companion computers and ground stations!

# 固定翼

# Position Mode (FW)

Position mode is an easy-to-fly RC mode in which, when the sticks are released/centered, the vehicle will level and fly a straight line ground track in the current direction — compensating for wind and other forces.

The throttle determines airspeed (at 50% throttle the aircraft will hold its current altitude with a preset cruise speed). Pitch is used to ascend/descend. Roll, pitch and yaw are all angle-controlled (so it is impossible to roll over or loop the vehicle).

提示

Position mode is the safest fixed-wing manual mode for new fliers.

FW Position Mode

# Altitude Mode (FW)

Altitude mode makes it easier for users to control vehicle altitude, and in particular to reach and maintain a fixed altitude. The mode will not attempt to hold the vehicle course against wind.

The climb/descent rate is controlled via the pitch/elevator stick. Once centered the autopilot latches onto the current altitude and will maintain it during yaw/roll, and at any airspeed. The throttle input controls airspeed. Roll and pitch are angle-controlled (so it is impossible to roll over or loop the vehicle).

When all remote control inputs are centered (no roll, pitch, yaw, and ~50% throttle) the aircraft will return to straight, level flight (subject to wind) and keep its current altitude.

提示

Altitude mode is the safest non GPS guided mode appropriate for beginners learning how to fly. It is just like Manual mode but additionally stabilizes the vehicle altitude when the pitch stick is released.

FW Altitude Mode

# Stabilized Mode (FW)

Stabilized mode puts the vehicle into straight and level flight when the RC sticks are centered, maintaining the horizontal posture against wind (but not vehicle heading and altitude).

The vehicle climb/descends based on pitch input and performs a coordinated turn if the roll/pitch sticks are non-zero. Roll and pitch are angle controlled (you can't roll upside down or loop).

提示

Stabilized mode is much easier to fly than Manual mode because you can't roll or flip it, and it is easy to level the vehicle by centering the control sticks.

The vehicle will glide if the throttle is lowered to 0% (motor stops). In order to perform a turn the command must beheld throughout the maneuver because if the roll is released the plane will stop turning and level itself (the same is true for pitch and yaw commands).

FW Manual Flight

# Acro Mode (FW)

Acro mode is the RC mode for performing acrobatic maneuvers e.g. rolls, flips, stalls and acrobatic figures.

The roll, pitch and yaw sticks control the rate of angular rotation around the respective axes and throttle is passed directly to the output mixer. When sticks are centered the vehicle will stop rotating, but remain in its current orientation (on its side, inverted, or whatever) and moving according to its current momentum.

FW Manual Acrobatic Flight

# Manual Mode (FW)

Manual mode sends RC stick input directly to the output mixer for "fully" manual control.

提示

This is the hardest mode to fly, because nothing is stabilised. Unlike Acro Mode if the RP stick is centered the vehicle will not automatically stop rotating around the axis - the pilot actually has to move the stick to apply force in the other direction.

注解

This is the only mode that overrides the FMU (commands are sent via the safety coprocessor). It provides a safety mechanism that allows full control of throttle, elevator, ailerons and rudder via RC in the event of an FMU firmware malfunction.

# Hold Mode (FW)

Hold causes a fixed-wing vehicle to start circling around the current position at its current altitude. The mode can be used to pause a mission or to help regain control of a vehicle in an emergency. It can be activated with a pre-programmed RC switch or the QGroundControl Pause button.

# Return Mode (FW)

Return mode causes the vehicle to fly a clear path to a safe location. The mode may be activated manually (via a pre-programmed RC switch) or automatically (i.e. in the event of a failsafe being triggered).

The return behaviour depends on parameter settings, and may follow a mission path and/or mission landing pattern (if defined). By default a fixed wing vehicle will ascend to a safe height and use a mission landing pattern if one exists, otherwise it will fly to the home position and circle.

# Mission Mode (FW)

Mission mode causes the vehicle to execute a predefined autonomous mission (flight plan) that has been uploaded to the flight controller. The mission is typically created and uploaded with a Ground Control Station (GCS) application.

提示

The PX4 GCS is called QGroundControl (opens new window). QGroundControl is the same application we use for configuring PX4.

# Takeoff Mode (FW)

Takeoff mode initiates the vehicle takeoff sequence. The specific launch behaviour depends on the configured takeoff mode (catapult/hand-launch mode or runway takeoff mode).

# Land Mode (FW)

Land mode causes the vehicle to turn and land at the location at which the mode was engaged. Fixed wing landing logic and parameters are explained in the topic: Landing (Fixed Wing).

# Offboard Mode (FW)

Offboard mode causes the fixed wing vehicle to obey attitude setpoints provided over MAVLink.

注解

This mode is intended for vehicle control from companion computers and ground stations!

# 垂直起降(VTOL)

A VTOL aircraft can fly as either a multicopter or as fixed-wing vehicle. The multicopter mode is mainly used for take off and landing while the fixed wing mode is used for efficient travel and/or mission execution.

Generally the flight modes for VTOL vehicles are the same as for multicopter when flying in MC mode and fixed-wing when flying in FW mode.

The switch between modes is initiated either by the pilot using an RC switch or automatically by PX4 when needed in the Auto modes.

A few notes:

  • VTOL Return mode uses a mission landing by default, if defined.

# Rover/Boat

Ground vehicles and boats only support manual mode and mission mode (while you can switch to other modes, these all behave just like manual mode).

# Manual Mode (UGV)

注解

This mode is enabled unless mission mode is set.

Manual modestops motors when RC control sticks are centered. To move the vehicle you move the sticks outside of the center.

As soon as you release the control sticks they will return to the center deadzone. This will turn off the motors and center the wheels/rudder. There is no active braking, so the vehicle may continue to move until its momentum dissipates (and for a boat, continue to drift).

# Mission Mode (UGV)

Mission modecauses the vehicle to execute a predefined autonomous mission (flight plan) that has been uploaded to the flight controller. The mission is typically created and uploaded with a Ground Control Station (GCS) application.

提示

The PX4 GCS is called QGroundControl (opens new window). QGroundControl is the same application we use for configuring PX4.

# Further Information