diff --git a/assets/protocols/flight_modes/altitude_icon.svg b/assets/protocols/flight_modes/altitude_icon.svg new file mode 100644 index 000000000..c4ce8d1a0 --- /dev/null +++ b/assets/protocols/flight_modes/altitude_icon.svg @@ -0,0 +1,168 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + image/svg+xml + + + + + + + + ALT + + + diff --git a/assets/protocols/flight_modes/position_fixed.svg b/assets/protocols/flight_modes/position_fixed.svg new file mode 100644 index 000000000..6d29514da --- /dev/null +++ b/assets/protocols/flight_modes/position_fixed.svg @@ -0,0 +1,44 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/en/SUMMARY.md b/en/SUMMARY.md index dcd08eee2..d566151eb 100644 --- a/en/SUMMARY.md +++ b/en/SUMMARY.md @@ -50,6 +50,7 @@ * [Command Protocol](services/command.md) * [Camera Protocol](services/camera.md) * [Camera Definition](services/camera_def.md) + * [Common Flight Modes Microservice](services/flight_modes.md) * [Gimbal Protocol](services/gimbal.md) * [Arm Authorization Protocol](services/arm_authorization.md) * [Image Transmission Protocol](services/image_transmission.md) diff --git a/en/services/flight_modes.md b/en/services/flight_modes.md new file mode 100644 index 000000000..f5a3d1524 --- /dev/null +++ b/en/services/flight_modes.md @@ -0,0 +1,494 @@ +# Common Flight Mode Microservice + +> **Warning** This microservices is still under construction (some initial thinking [here](https://docs.google.com/document/d/1LIcfOL3JrX-EznvXArna1h-sZ7va7LRTteIUzISuD8c/edit)). + At the moment only base modes are standarized - custom mode/sub mode are currently completely at the discretion of the flight stack. + We hope to also standardise some of those custom modes (hence the page). + +*Flight Modes* define how the autopilot responds to user input and controls vehicle movement. +This topic lists the baseline flight modes; flight modes that are commonly implemented by many MAVLink-enabled flight systems. + +Flight stacks are not required to implement these modes, but if they do they must reference them using the same base and custom mode, and implement the same behaviour as described below. +This allows a ground station or other MAVLink application to control the vehicle even if it is not familiar with the vehicle flight stack. + +> **Note** The tables below describe the "high level" behaviour for fixed wing and copter ([table key is below](#key)). + Minor variations in behaviour are expected for different implementations; but a user or GCS should not need more information than provided here to enable or provide a UI for the mode. + + +## Base Modes + +Flight modes are set using [MAV_CMD_DO_SET_MODE](../messages/common.md#MAV_CMD_DO_SET_MODE), specifying a "base" mode ([MAV_MODE](../messages/common.md#MAV_MODE)) and custom mode/sub-mode. The `MAV_MODE` is itself a predefined OR of mode definitions in [MAV_MODE_FLAG](../messages/common.md#MAV_MODE_FLAG) which define the "base" behaviour. + +The base modes are: + +- **Manual:** Direct pass-through of pilot (RC) input to outputs. + This only applies to planes (multicopters *require* stabilization/attitude control). + +- **Stabilized:** Pilot in the loop with *attitude control*. + Roll/pitch are controlled by stick position, yaw rate by stick position. + +- **Guided:** Pilot in the loop with *position control*. + X/Y velocity are controlled by stick position, yaw rate by stick position. + +- **Auto:** Flight modes where vehicle is under autonomous control (e.g. missons, go-to commands, takeoff/land etc., and where RC control is not *required* (e.g. it is optional as in [Orbit mode](#orbit_mc)). + + + + + + +## Fixed Wing + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
ModeBase ModeRoll & PitchYawThrottlePosition SensorsSummary
PositionGuidedS+S+S+

RC mode where centered sticks put vehicle into straight and level flight where vehicle posture/attitude, altitude, and the straight line vehicle path are maintained against wind (and other forces). +

    +
  • Centered RC RPY sticks – level flight that follows a straight line ground track in the current direction against any wind.
  • +
  • Outside center: +
      +
    • Pitch stick controls altitude (same as Altitude).
    • +
    • Roll stick controls roll angle. Autopilot will maintain coordinated flight (same as Stabilized).
    • +
    • Throttle sets airspeed (same as Altitude).
    • +
    • Roll, pitch and yaw are all angle-controlled (so it is impossible to roll over or loop the vehicle).
    • +
    • Yaw stick actuates the rudder (signal will be added to the one calculated by the autopilot to maintain coordinated flight). This is the same as Stabilized.
    • +
  • +
+

+
AltitudeStabilized

S (roll)

S+(pitch)

MS+ +

RC mode like Stabilized mode but with altitude stabilization (centered sticks put vehicle into straight and level flight and maintain current altitude). The vehicle course is not maintained, and can drift due to wind. +

    +
  • Centered RPY sticks (inside deadband): +
      +
    • Autopilot maintains altitude with wings also level.
    • +
    • Throttle stick controls the airspeed of the aircraft if an airspeed sensor is connected (without airspeed sensor, the user cannot control throttle).
    • +
    +
  • Outside center: +
      +
    • Pitch stick controls altitude.
    • +
    • Throttle stick controls the airspeed of the aircraft (as for centered RPY sticks).
    • +
    • Yaw stick actuates the rudder (signal will be added to the one calculated by the autopilot to maintain coordinated flight). This is the same as Stabilized.
    • +
    +
  • +
+

+
StabilizedStabilizedSMM +

RC mode where centered RP sticks levels vehicle attitude (roll and pitch). The vehicle course and altitude are not maintained, and can drift due to wind.

+
    +
  • Pitch stick controls pitch angle.
  • +
  • Roll stick controls roll angle. Autopilot will maintain coordinated flight.
  • +
  • Throttle stick controls throttle.
  • +
  • Yaw stick actuates the rudder (signal will be added to the one calculated by the autopilot to maintain coordinated flight).
  • +
+
AcroStabilizedSrateSrateM

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

+

RPY stick inputs are translated to angular rate commands that are stabilized by autopilot. Throttle is passed directly to the output mixer.

ManualManualMMM

RC mode where stick input is sent directly to the output mixer (for "fully" manual control).

+

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. +

+
TakeoffAuto Vehicle initiates the takeoff sequence using either catapult/hand-launch mode or runway takeoff mode (in the current direction).
LandAuto Vehicle initiates a fixed-wing landing sequence.
HoldAuto Vehicle circles around the GPS hold position at the current altitude.
ReturnAuto Vehicle ascends to a safe height and then returns to its home position and circles.
MissionAuto Vehicle executes a predefined mission/flight plan that has been uploaded to the flight controller.
OffboardAuto Vehicle obeys attitude setpoints provided over MAVLink (often from a companion computer connected via serial cable or wifi).
+ + + +## Multicopter + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
ModeBase ModeRoll & PitchYawThrottlePosition SensorsSummary
PositionGuidedS+SrateS+

RC mode where RPT sticks control speed in corresponding directions. Centered sticks level vehicle and hold it to fixed position and altitude against wind. +

    +
  • Centered RPT sticks hold x, y, z position steady against any wind and levels attitude.
  • +
  • Outside center: +
      +
    • Roll/Pitch sticks control speed over ground in left-right and forward-back directions (respectively) relative to the "front" of the vehicle.
    • +
    • Throttle stick controls speed of ascent-descent.
    • +
    • Yaw stick controls rate of angular rotation above the horizontal plane.
    • +
    +
  • +
  • Takeoff: +
      +
    • When landed, the vehicle will take off if the throttle stick is raised above 62.5% percent (of the full range from bottom).
    • +
    +
  • +
+ + +

+
AltitudeStabilizedSSrateS+

RC mode like Manual/Stabilized mode but with altitude stabilization (centered sticks level vehicle and hold it to fixed altitude). The horizontal position of the vehicle can move due to wind (or pre-existing momentum). +

    +
  • Centered sticks (inside deadband): +
      +
    • RPY sticks levels vehicle.
    • +
    • Throttle (~50%) holds current altitude steady against wind.
    • +
    +
  • Outside center: +
      +
    • Roll/Pitch sticks control tilt angle in respective orientations, resulting in corresponding left-right and forward-back movement.
    • +
    • Throttle stick controls up/down speed with a predetermined maximum rate (and movement speed in other axes).
    • +
    • Yaw stick controls rate of angular rotation above the horizontal plane.
    • +
    +
  • +
  • Takeoff: +
      +
    • When landed, the vehicle will take off if the throttle stick is raised above 62.5% percent (of the full range from bottom).
    • +
    +
  • +
+

+
Manual/ StabilizedStabilizedSSrateM

RC mode where centered sticks level vehicle (only - position is not stabilized).

+

+

    +
  • Centered RP sticks level vehicle.
  • +
  • Outside center: +
      +
    • Roll/Pitch sticks control tilt angle in those orientations, resulting in corresponding left-right and forward-back movement.
    • +
    • Throttle stick controls up/down speed (and movement speed in other axes).
    • +
    • Yaw stick controls rate of angular rotation above the horizontal plane.
    • +
    +
  • +
+

+

RattitudeStabilizedS or SrateSrateM +

RC mode that allows pilots to fly using Manual/Stabilized flight most of the time, but still perform Acro mode-style flips and tricks when desired. Centered sticks level vehicle. +

    +
  • Sticks within mode's threshold (like Manual/Stabilized mode). +
      +
    • Centered RP sticks level vehicle. Roll/Pitch sticks control tilt angle in those orientations, resulting in corresponding left-right and forward-back movement.
    • +
    +
  • +
  • Sticks outside threshold (like Acro mode): +
      +
    • RPY stick inputs control the rate of angular rotation around the respective axes.
    • +
    +
  • +
+

+
AcroStabilizedSrateSrateM

RC mode for performing acrobatic maneuvers e.g. flips, rolls and loops.

+

RC RPY stick inputs control the rate of angular rotation around the respective axes. Throttle is passed directly to the output mixer. When sticks are centered the vehicle will stop rotating, but remain in its current orientation (e.g. possibly inverted) and moving according to its current momentum.

+
OrbitGuided---

GCS-initiated guided mode for flying a circle, always facing the center.

+

Mode must be started from GCS, specifying center point and initial radius and altitude. RC control is optional, and can be used to set the orbit altitude, radius, speed, and direction. Altitude control is the same as for Position Mode.

+
TakeoffAuto Vehicle ascends to takeoff altitude and holds position.
LandAuto Vehicle lands at the position where the mode was engaged.
HoldAuto Vehicle hovers at the current GPS position and altitude.
ReturnAuto Vehicle ascends to a safe height and then returns to its home position and lands. +
MissionAuto Vehicle executes a predefined mission/flight plan that has been uploaded to the flight controller.
Follow MeAuto Vehicle autonomously follows a user using an Android phone/tablet running QGC.
OffboardAuto Vehicle obeys a position, velocity or attitude setpoints provided over MAVLink (often from a companion computer connected via serial cable or wifi).
+ + +## VTOL + +VTOL vehicles may support both fixed-wing and multicopter flight modes, executing them based on the current vehicle mode (MC or FW). + + +## Key + +Key for understanding the table is as follows: + +Symbol | Description +--- | --- +M | Manual control via RC sticks. RC input is sent directly to the output mixer. +S | Assistance from autopilot to stabilize the attitude. RC input is required. Position of RC stick maps to the orientation of vehicle. +Srate | Assistance from autopilot to stabilize the attitude rate. RC input is required. Position of RC stick maps to the rate of rotation of vehicle in that orientation. +S+ | Assistance from autopilot to hold position or altitude against wind. RC input is required. +Auto | This mode is automatic (RC control is disabled by default except to change modes). + | Sensor(s) that measures position/height needed e.g. optical flow, GPS+barometer, visual-inertial odometry. + | Sensor(s) that measures height/altitude needed e.g. barometer, rangefinder. + + +Abbreviations: +* RPY: Roll, Pitch, Yaw +* RPT: Roll, Pitch Throttle