PX4 User Guide
  • Introduction
  • Getting Started
    • Basic Concepts
    • Vehicles/Frames
    • Flight Controllers
    • Sensors
    • Radio Systems
    • Flight Modes
    • Vehicle Status Notifications
      • LED Meanings
      • Tune/Sound Meanings
      • Preflight Checks
    • Payloads & Cameras
    • Flight Reporting
  • Basic Assembly
    • Mounting the Flight Controller
    • Mounting the GPS/Compass
    • Vibration Isolation
    • Cable Wiring
    • CUAV Pixhawk V6X Wiring QuickStart
    • CUAV V5+ Wiring Quickstart
    • CUAV V5 nano Wiring Quickstart
    • Holybro Pixhawk 6C Wiring Quickstart
    • Holybro Pixhawk 6X Wiring Quickstart
    • Holybro Pixhawk 5X Wiring Quickstart
    • Holybro Pixhawk 4 Wiring Quickstart - Discontinued
    • Holybro Pixhawk 4 Mini Wiring Quickstart - Discontinued
    • Holybro Durandal Wiring Quickstart
    • Holybro Pix32 v5 Wiring Quickstart
    • Cube Wiring Quickstart
    • Pixracer Wiring Quickstart
    • mRo (3DR) Pixhawk Wiring Quickstart
  • Standard Configuration
    • Firmware
    • Airframe
    • Sensor Orientation
    • Compass
    • Gyroscope
    • Accelerometer
    • Airspeed
    • Level Horizon Calibration
    • Radio Setup
    • Joystick Setup
    • Flight Modes
    • Battery
    • Safety
      • Failsafe Simulation
    • ESC Calibration
    • Actuators
    • Autotune
  • Vehicle Types & Setup
    • Multicopters
      • Multicopter Config/Tuning
        • MC Filter/Control Latency Tuning
        • MC PID Tuning (Manual/Basic)
        • MC PID Tuning Guide (Manual/Advanced)
        • MC Setpoint Tuning (Trajectory Generator)
          • MC Jerk-limited Type Trajectory
        • Multicopter Racer Setup
      • X500 v2 (Pixhawk 6C)
      • X500 v2 (Pixhawk 5X)
      • X500 (Pixhawk 4)
      • S500 V2 (Pixhawk 4)
      • DJI F450 (CUAV v5+)
      • DJI F450 (CUAV v5 nano)
      • QAV250 (Pixhawk4 Mini) - Discontinued
      • DJI F450 + RTK (Pixhawk 3 Pro)
      • QAV250 (Pixhawk Mini)
      • QAV-R 5" Racer (Pixracer)
      • Omnicopter
    • Planes
      • Fixed Wing Config/Tuning
        • Fixedwing PID Tuning Guide
        • Fixedwing Advanced Tuning Guide
        • Fixedwing Trimming Guide
      • Reptile Dragon 2 (ARK6X)
      • Turbo Timber Evolution (Pixhawk 4 Mini)
      • Wing Wing Z84 (Pixracer)
    • VTOL
      • VTOL Config/Tuning
        • QuadPlane Configuration
        • Back-transition Tuning
        • VTOL w/o Airspeed Sensor
        • VTOL Weather Vane
      • Standard VTOL
        • FunCub QuadPlane (Pixhawk)
        • Ranger QuadPlane (Pixhawk)
        • Falcon Vertigo QuadPlane (Dropix)
      • Tailsitter VTOL
        • Build: TBS Caipiroshka Tailsitter Build (Pixracer)
      • Tiltrotor VTOL
        • Build: Convergence Tiltrotor (Pixfalcon)
    • Airships (experimental)
    • Autogyros (experimental)
      • ThunderFly Auto-G2 (Holybro pix32)
    • Balloons (experimental)
    • Helicopter (experimental)
      • Helicopter Config/Tuning
    • Rovers (experimental)
      • Traxxas Stampede
    • Submarines (experimental)
      • BlueROV2
    • Airframes Reference
  • Flying
    • First Flight Guidelines
    • Flying 101
    • Missions
      • Package Delivery Mission
    • GeoFence
    • Safety Point Planning
    • Flight Modes
      • Position Mode (MC)
      • Altitude Mode (MC)
      • Manual/Stabilized Mode (MC)
      • Acro Mode (MC)
      • Orbit Mode (MC)
      • Position Mode (FW)
      • Altitude Mode (FW)
      • Stabilized Mode (FW)
      • Acro Mode (FW)
      • Manual Mode (FW)
      • Takeoff Mode
      • Land Mode
      • Return Mode
      • Hold Mode
      • Mission Mode
      • Follow Me Mode
      • Offboard Mode
    • Terrain Following/Holding
  • Flight Log Analysis
    • Log Analysis using Flight Review
    • Log Analysis using PlotJuggler
  • Advanced Configuration
    • Finding/Updating Parameters
    • Full Parameter Reference
    • ECL/EKF Overview & Tuning
    • Flight Termination Configuration
    • Bootloader Flashing onto Betaflight Systems
    • Land Detector Configuration
    • Prearm/Arm/Disarm Configuration
    • IMU Factory Calibration
    • Sensor Thermal Compensation
    • Compass Power Compensation
    • Advanced Controller Orientation
    • Static Pressure Buildup
    • Serial Port Configuration
    • MAVLink Telemetry (OSD/GCS)
    • PX4 Ethernet Setup
    • Bootloader Update
  • Hardware (Drones&Parts)
    • Complete Vehicles
      • ModalAI Starling
      • PX4 Vision Kit
      • MindRacer BNF & RTF
        • MindRacer 210
        • NanoMind 110
      • Holybro Kopis 2
      • Bitcraze Crazyflie 2.1
    • Flight Controllers (Autopilots)
      • Pixhawk Series
        • Silicon Errata
      • Pixhawk Standard Autopilots
        • CUAV Pixhawk V6X (FMUv6X)
        • Holybro Pixhawk 6X (FMUv6X)
        • Holybro Pixhawk 6C (FMUv6C)
        • Holybro Pixhawk 6C Mini(FMUv6C)
        • Holybro Pix32 v6 (FMUv6C)
        • Holybro Pixhawk 5X (FMUv5X)
        • Holybro Pixhawk 4 (FMUv5) - Discontinued
        • Holybro Pixhawk 4 Mini (FMUv5) - Discontinued
        • Drotek Pixhawk 3 Pro (FMUv4pro)
        • mRo Pixracer (FMUv4)
        • Hex Cube Black (FMUv3)
        • mRo Pixhawk (FMUv3)
        • Holybro Pixhawk Mini (FMUv3) - Discontinued
      • Manufacturer-Supported Autopilots
        • AirMind MindPX
        • AirMind MindRacer
        • ARK Electronics ARKV6X
        • CUAV X7
        • CUAV Nora
        • CUAV V5+ (FMUv5)
        • CUAV V5 nano (FMUv5)
        • CUAV Pixhack v3 (FMUv3)
        • CubePilot Cube Orange+ (CubePilot)
        • CubePilot Cube Orange (CubePilot)
        • CubePilot Cube Yellow (CubePilot)
        • Holybro Kakute H7v2
        • Holybro Kakute H7mini
        • Holybro Kakute H7
        • Holybro Durandal
        • Holybro Pix32 v5
        • ModalAI Flight Core v1
        • ModalAI VOXL Flight
        • ModalAI VOXL 2
        • mRobotics-X2.1 (FMUv2)
        • mRo Control Zero F7)
        • NXP RDDRONE-FMUK66 FMU
        • Sky-Drones AIRLink
        • SPRacing SPRacingH7EXTREME
        • ThePeach FCC-K1
        • ThePeach FCC-R1
      • Experimental Autopilots
        • BeagleBone Blue
        • Raspberry Pi 2/3 Navio2
        • Raspberry Pi 2/3/4 PilotPi
          • PilotPi with Raspberry Pi OS
          • PilotPi with Ubuntu Server
      • Discontinued Autopilots/Vehicles
        • Drotek Dropix (FMUv2)
        • Omnibus F4 SD
        • BetaFPV Beta75X 2S Brushless Whoop
        • Bitcraze Crazyflie 2.0
        • Aerotenna OcPoC-Zynq Mini
        • CUAV v5
        • Holybro Kakute F7 (Discontinued)
        • Holybro Pixfalcon
        • Holybro pix32 (FMUv2)
        • mRo AUAV-X2
        • 3DR Pixhawk 1
        • Snapdragon Flight
        • Intel® Aero RTF Drone (Discontinued)
      • Pixhawk Autopilot Bus (PAB) & Carriers
        • ARK Electronics Pixhawk Autopilot Bus Carrier
    • Flight Controller Peripherals
      • ADSB/FLARM (Traffic Avoidance)
      • Air Traffic Avoidance: ADSB/FLARM
      • Air Traffic Avoidance: UTM
      • Airspeed Sensors
        • TFSlot Airspeed Sensor
      • Barometers
      • Camera
      • Distance Sensors (Rangefinders)
        • Lightware SFxx Lidar
        • Ainstein US-D1 Standard Radar Altimeter
        • LeddarOne Lidar
        • Benewake TFmini Lidar
        • Lidar-Lite
        • TeraRanger
        • Lanbao PSK-CM8JL65-CC5
        • Avionics Anonymous Laser Altimeter UAVCAN Interface
      • ESCs & Motors
        • PWM ESCs and Servos
        • DShot ESCs
        • OneShot ESCs and Servos
        • DroneCAN ESCs
          • Zubax Telega
          • PX4 Sapog ESC Firmware
            • Holybro Kotleta
            • Zubax Orel
        • VESC
      • TBS Crossfire (CRSF) Telemetry
      • FrSky Telemetry
      • Gimbal (Mount) Configuration
      • GPS/Compass
        • ARK GPS
        • Holybro DroneCAN M8N GPS
        • LOCOSYS Hawk A1 GNSS
        • Hex Here2
        • Holybro M8N & M9N GPS
        • Sky-Drones SmartAP GPS
      • Grippers
        • Servo Gripper
      • Optical Flow
        • ARK Flow
        • PMW3901
        • PX4FLOW (Deprecated)
      • Precision Landing
      • Parachute
      • Power Modules/PDB
        • CUAV HV pm
        • CUAV CAN PMU
        • Holybro PM02
        • Holybro PM07
        • Holybro PM06 V2
        • Holybro PM02D (digital)
        • Holybro PM03D (digital)
        • Pomegranate Systems Power Module
        • Sky-Drones SmartAP PDB
      • Satellite Coms (Iridium/RockBlock)
      • Telemetry Radios
        • SiK Radio
          • RFD900 (SiK) Telemetry Radio
          • HolyBro (SIK) Telemetry Radio
        • Telemetry Wifi
          • ESP8266 WiFi Module
          • ESP32 WiFi Module
          • 3DR Telemetry Wifi (Discontinued)
        • Microhard Serial Telemetry Radio
          • ARK Electron Microhard Serial Telemetry Radio
          • Holybro Microhard P900 Telemetry Radio
        • CUAV P8 Telemetry Radio
        • HolyBro XBP9X - Discontinued
      • RTK GPS
        • ARK RTK GPS
        • RTK GPS Heading with Dual u-blox F9P
        • CUAV C-RTK
        • CUAV C-RTK2 PPK/RTK GNSS
        • CUAV C-RTK 9Ps
        • Femtones MINI2 Receiver
        • Freefly RTK GPS
        • Holybro H-RTK-F9P
        • Holybro H-RTK-M8P
        • Holybro H-RTK Unicore UM982 GPS
        • Locosys Hawk R1
        • Locosys Hawk R2
        • Septentrio AsteRx-RIB
        • Septentrio mosaic-go
        • Trimble MB-Two
        • CubePilot Here+ (Discontined)
      • Remote ID
      • Smart Batteries
        • Rotoye Batmon Battery Smartification Kit
      • Tachometers (Revolution Counters)
        • ThunderFly TFRPM01 Tachometer Sensor
      • I2C Peripherals
        • I2C bus accelerators
        • TFI2CADT01 I2C address translator
      • CAN Peripherals
      • DroneCAN Peripherals
        • PX4 DroneCAN Firmware
        • ARK CANnode
    • Companion Computers
      • Pixhawk + Companion Setup
        • RasPi Pixhawk Companion
      • Companion Computer Peripherals
      • Holybro Pixhawk RPI CM4 Baseboard
      • Auterion Skynode
      • Computer Vision
        • Obstacle Avoidance
        • Safe Landing
        • Collision Prevention
        • Path Planning Interface
        • Motion Capture (MoCap)
        • Visual Inertial Odometry (VIO)
          • Realsense T265 Tracking Camera (VIO)
      • Video Streaming
  • Development
    • Getting Started
      • Recommended Hardware/Setup
      • Toolchain Installation
        • MacOS Setup
        • Ubuntu Setup
        • Windows Setup
        • Visual Studio Code IDE
        • Other/Generic Tools
      • Building the Code
      • Writing your First Application
      • Application/Module Template
    • Concepts
      • PX4 Architecture
      • PX4 Flight Stack Architecture
        • Controller Diagrams
      • Events Interface
      • Flight Modes
      • Flight Tasks
      • Control Allocation
      • PWM limit state machine
      • System Startup
      • SD Card Layout
    • Simulation
      • jMAVSim Simulation
        • Multi-Vehicle Sim with JMAVSim
      • Gazebo Simulation
        • Vehicles
        • Multi-Vehicle Sim
      • Gazebo Classic Simulation
        • Vehicles
        • Worlds
        • Multi-Vehicle Sim
      • FlightGear Simulation
        • FlightGear Vehicles
        • Multi-Vehicle Sim with FlightGear
      • JSBSim Simulation
      • AirSim Simulation
      • Multi-Vehicle Simulation
      • Simulate Failsafes
      • HITL Simulation
      • Simulation-In-Hardware
    • Hardware
      • Flight Controller Reference Design
      • Manufacturer’s Board Support Guide
      • Flight Controller Porting Guide
        • PX4 Board Configuration (kconfig)
        • NuttX Board Porting Guide
      • Serial Port Mapping
      • Airframes
        • Adding a New Airframe
      • Device Drivers
      • Telemetry Radio
        • SiK Radio
      • Sensor and Actuator I/O
        • DroneCAN
        • I2C Bus
        • UART/Serial Ports
          • Port-Configurable Serial Drivers
      • RTK GPS (Integration)
    • Middleware
      • uORB Messaging
      • uORB Graph
      • uORB Message Reference
        • ActionRequest
        • ActuatorArmed
        • ActuatorControlsStatus
        • ActuatorMotors
        • ActuatorOutputs
        • ActuatorServos
        • ActuatorServosTrim
        • ActuatorTest
        • AdcReport
        • Airspeed
        • AirspeedValidated
        • AirspeedWind
        • AutotuneAttitudeControlStatus
        • BatteryStatus
        • ButtonEvent
        • CameraCapture
        • CameraStatus
        • CameraTrigger
        • CellularStatus
        • CollisionConstraints
        • CollisionReport
        • ControlAllocatorStatus
        • Cpuload
        • DebugArray
        • DebugKeyValue
        • DebugValue
        • DebugVect
        • DifferentialPressure
        • DistanceSensor
        • Ekf2Timestamps
        • EscReport
        • EscStatus
        • EstimatorAidSource1d
        • EstimatorAidSource2d
        • EstimatorAidSource3d
        • EstimatorBias
        • EstimatorBias3d
        • EstimatorEventFlags
        • EstimatorGpsStatus
        • EstimatorInnovations
        • EstimatorSelectorStatus
        • EstimatorSensorBias
        • EstimatorStates
        • EstimatorStatus
        • EstimatorStatusFlags
        • Event
        • FailsafeFlags
        • FailureDetectorStatus
        • FollowTarget
        • FollowTargetEstimator
        • FollowTargetStatus
        • GeneratorStatus
        • GeofenceResult
        • GimbalControls
        • GimbalDeviceAttitudeStatus
        • GimbalDeviceInformation
        • GimbalDeviceSetAttitude
        • GimbalManagerInformation
        • GimbalManagerSetAttitude
        • GimbalManagerSetManualControl
        • GimbalManagerStatus
        • GpioConfig
        • GpioIn
        • GpioOut
        • GpioRequest
        • GpsDump
        • GpsInjectData
        • Gripper
        • HealthReport
        • HeaterStatus
        • HomePosition
        • HoverThrustEstimate
        • InputRc
        • InternalCombustionEngineStatus
        • IridiumsbdStatus
        • IrlockReport
        • LandingGear
        • LandingGearWheel
        • LandingTargetInnovations
        • LandingTargetPose
        • LaunchDetectionStatus
        • LedControl
        • LogMessage
        • LoggerStatus
        • MagWorkerData
        • MagnetometerBiasEstimate
        • ManualControlSetpoint
        • ManualControlSwitches
        • MavlinkLog
        • MavlinkTunnel
        • Mission
        • MissionResult
        • ModeCompleted
        • MountOrientation
        • NavigatorMissionItem
        • NormalizedUnsignedSetpoint
        • NpfgStatus
        • ObstacleDistance
        • OffboardControlMode
        • OnboardComputerStatus
        • OrbTest
        • OrbTestLarge
        • OrbTestMedium
        • OrbitStatus
        • ParameterUpdate
        • Ping
        • PositionControllerLandingStatus
        • PositionControllerStatus
        • PositionSetpoint
        • PositionSetpointTriplet
        • PowerButtonState
        • PowerMonitor
        • PpsCapture
        • PwmInput
        • Px4ioStatus
        • QshellReq
        • QshellRetval
        • RadioStatus
        • RateCtrlStatus
        • RcChannels
        • RcParameterMap
        • Rpm
        • RtlTimeEstimate
        • SatelliteInfo
        • SensorAccel
        • SensorAccelFifo
        • SensorBaro
        • SensorCombined
        • SensorCorrection
        • SensorGnssRelative
        • SensorGps
        • SensorGyro
        • SensorGyroFft
        • SensorGyroFifo
        • SensorHygrometer
        • SensorMag
        • SensorOpticalFlow
        • SensorPreflightMag
        • SensorUwb
        • SensorSelection
        • SensorsStatus
        • SensorsStatusImu
        • SystemPower
        • TakeoffStatus
        • TaskStackInfo
        • TecsStatus
        • TelemetryStatus
        • TiltrotorExtraControls
        • TimesyncStatus
        • TrajectoryBezier
        • TrajectorySetpoint
        • TrajectoryWaypoint
        • TransponderReport
        • TuneControl
        • UavcanParameterRequest
        • UavcanParameterValue
        • UlogStream
        • UlogStreamAck
        • UwbDistance
        • UwbGrid
        • VehicleAcceleration
        • VehicleAirData
        • VehicleAngularAccelerationSetpoint
        • VehicleAngularVelocity
        • VehicleAttitude
        • VehicleAttitudeSetpoint
        • VehicleCommand
        • VehicleCommandAck
        • VehicleConstraints
        • VehicleControlMode
        • VehicleGlobalPosition
        • VehicleImu
        • VehicleImuStatus
        • VehicleLandDetected
        • VehicleLocalPosition
        • VehicleLocalPositionSetpoint
        • VehicleMagnetometer
        • VehicleOdometry
        • VehicleOpticalFlow
        • VehicleOpticalFlowVel
        • VehicleRatesSetpoint
        • VehicleRoi
        • VehicleStatus
        • VehicleThrustSetpoint
        • VehicleTorqueSetpoint
        • VehicleTrajectoryBezier
        • VehicleTrajectoryWaypoint
        • VtolVehicleStatus
        • Wind
        • YawEstimatorStatus
      • MAVLink Messaging
      • uXRCE-DDS (PX4-ROS 2/DDS Bridge)
    • Modules & Commands
      • Autotune
      • Commands
      • Communication
      • Controllers
      • Drivers
        • Airspeed Sensor
        • Baro
        • Distance Sensor
        • IMU
        • INS
        • Magnetometer
        • Optical Flow
        • Rpm Sensor
        • Transponder
      • Estimators
      • Simulations
      • System
      • Template
    • Debugging/Logging
      • FAQ
      • Consoles/Shells
        • MAVLink Shell
        • System Console
      • Debugging with GDB
        • SWD Debug Port
        • JLink Probe
        • Black Magic/DroneCode Probe
        • STLink Probe
        • Hardfault Debugging
      • Debugging with Eclipse
      • Failure Injection
      • Sensor/Topic Debugging
      • Simulation Debugging
      • Sending Debug Values
      • System-wide Replay
      • Profiling
      • Binary Size Profiling
      • Logging
      • Flight Log Analysis
      • ULog File Format
    • Tutorials
      • Long-distance Video Streaming
      • Connecting an RC Receiver on Linux
    • Advanced Topics
      • Parameters & Configs
      • Package Delivery Architecture
      • Computer Vision
        • Motion Capture (VICON, Optitrack, NOKOV)
      • Installing driver for Intel RealSense R200
      • Switching State Estimators
      • Out-of-Tree Modules
      • STM32 Bootloader
      • System Tunes
      • Advanced Linux Installation Cases
      • Windows Cygwin Toolchain Maintenance
      • Unsupported Developer Setup
        • CentOS Linux
        • Arch Linux
        • Windows VM Toolchain
        • Windows Cygwin Toolchain
        • Qt Creator IDE
    • Platform Testing and CI
      • Test Flights
        • Test MC_01 - Manual Modes
        • Test MC_02 - Full Autonomous
        • Test MC_03 - Auto Manual Mix
        • Test MC_04 - Failsafe Testing
        • Test MC_05 - Indoor Flight (Manual Modes)
      • Unit Tests
      • Continuous Integration
      • MAVSDK Integration Testing
      • ROS Integration Testing
      • Docker Containers
      • Maintenance
  • Drone Apps & APIs
    • Offboard Control from Linux
    • ROS
      • ROS 2
        • ROS 2 User Guide
        • ROS 2 Offboard Control Example
        • ROS 2 Multi Vehicle Simulation
      • ROS 1 with MAVROS
        • ROS/MAVROS Installation Guide
        • ROS/MAVROS Offboard Example (C++)
        • ROS/MAVROS Offboard Example (Python)
        • ROS/MAVROS Sending Custom Messages
        • ROS/MAVROS with Gazebo Classic Simulation
        • Gazebo Classic OctoMap Models with ROS 1
        • ROS/MAVROS Installation on RPi
        • External Position Estimation (Vision/Motion based)
    • DroneKit
  • Contribution (&Dev Call)
    • Dev Call
    • Support
    • Source Code Management
      • GIT Examples
    • Documentation
    • Translation
    • Terminology/Notation
    • Licenses
  • Releases
    • 1.14
    • 1.13
    • 1.12
Powered by GitBook
On this page
  • Tuning Steps
  • Rate Controller
  • Attitude Controller
  • Thrust Curve
  • Airmode & Mixer Saturation
  1. Vehicle Types & Setup
  2. Multicopters
  3. Multicopter Config/Tuning

MC PID Tuning Guide (Manual/Advanced)

PreviousMC PID Tuning (Manual/Basic)NextMC Setpoint Tuning (Trajectory Generator)

Last updated 1 year ago

This topic provides detailed information about PX4 controllers, and how they are tuned.

:::tip is recommended for tuning the vehicles around the hover thrust point, as the approach described is intuitive, easy, and fast. This is all that is required for many vehicles. :::

Use this topic when tuning around the hover thrust point is not sufficient (e.g. on vehicles where there are non-linearities and oscillations at higher thrusts). It is also useful for a deeper understanding of how the basic tuning works, and to understand how to use the setting.

Tuning Steps

:::note For safety reasons, the default gains are set to low values. You must increase the gains before you can expect good control responses. :::

Here are some general points to follow when tuning:

  • All gains should be increased very slowly as large gains may cause dangerous oscillations! Typically increase gains by 20-30% per iteration, reducing to 5-10% for final fine tuning.

  • Land before changing a parameter. Slowly increase the throttle and check for oscillations.

  • Tune the vehicle around the hovering thrust point, and use the to account for thrust non-linearities or high-thrust oscillations.

  • Optionally enable the high-rate logging profile with the parameter so you can use the log to evaluate the rate and attitude tracking performance (the option can be disabled afterwards).

:::warning Always disable when tuning a vehicle. :::

Rate Controller

The rate controller is the inner-most loop with three independent PID controllers to control the body rates (yaw, pitch, roll).

:::note A well-tuned rate controller is very important as it affects all flight modes. A badly tuned rate controller will be visible in , for example, as "twitches" (the vehicle will not hold perfectly still in the air). :::

Rate Controller Architecture/Form

Users can select the form that is used by setting the proportional gain for the other form to "1" (i.e. in the diagram below set K to 1 for the parallel form, or P to 1 for the standard form - this will replace either the K or P blocks with a line).

  • G(s) represents the angular rates dynamics of a vehicle

  • r is the rate setpoint

  • y is the body angular rate (measured by a gyro)

  • e is the error between the rate setpoint and the measured rate

  • u is the output of the PID controller

The two forms are described below.

:::tip For more information see:

Parallel Form

The parallel form is the simplest form, and is (hence) commonly used in textbooks. In this case the output of the controller is simply the sum of the proportional, integral and derivative actions.

Standard Form

This form is mathematically equivalent to the parallel form, but the main advantage is that (even if it seems counter intuitive) it decouples the proportional gain tuning from the integral and derivative gains. This means that a new platform can easily be tuned by taking the gains of a drone with similar size/inertia and simply adjust the K gain to have it flying properly.

Rate PID Tuning

The related parameters for the tuning of the PID rate controllers are:

  • Acro mode is preferred, but is harder to fly. If you choose this mode, disable all stick expo:

    • MC_ACRO_EXPO = 0, MC_ACRO_EXPO_Y = 0, MC_ACRO_SUPEXPO = 0, MC_ACRO_SUPEXPOY = 0

    • MC_ACRO_P_MAX = 200, MC_ACRO_R_MAX = 200

    • MC_ACRO_Y_MAX = 100

  • Manual/Stabilized mode is simpler to fly, but it is also more difficult to see if the attitude or the rate controller needs more tuning.

If the vehicle does not fly at all:

  • If there are strong oscillations when first trying to takeoff (to the point where it does not fly), decrease all P and D gains until it takes off.

  • If the reaction to RC movement is minimal, increase the P gains.

The actual tuning is roughly the same in Manual mode or Acro mode: You iteratively tune the P and D gains for roll and pitch, and then the I gain. Initially you can use the same values for roll and pitch, and once you have good values, you can fine-tune them by looking at roll and pitch response separately (if your vehicle is symmetric, this is not needed). For yaw it is very similar, except that D can be left at 0.

Proportional Gain (P/K)

The proportional gain is used to minimize the tracking error (below we use P to refer to both P or K). It is responsible for a quick response and thus should be set as high as possible, but without introducing oscillations.

  • If the P gain is too high: you will see high-frequency oscillations.

  • If the P gain is too low:

    • the vehicle will react slowly to input changes.

    • In Acro mode the vehicle will drift, and you will constantly need to correct to keep it level.

Derivative Gain (D)

The D (derivative) gain is used for rate damping. It is required but should be set only as high as needed to avoid overshoots.

  • If the D gain is too high: the motors become twitchy (and maybe hot), because the D term amplifies noise.

  • If the D gain is too low: you see overshoots after a step-input.

Typical values are:

  • standard form (P = 1): between 0.01 (4" racer) and 0.04 (500 size), for any value of K

  • parallel form (K = 1): between 0.0004 and 0.005, depending on the value of P

Integral Gain (I)

The I (integral) gain keeps a memory of the error. The I term increases when the desired rate is not reached over some time. It is important (especially when flying Acro mode), but it should not be set too high.

  • If the I gain is too high: you will see slow oscillations.

  • If the I gain is too low: this is best tested in Acro mode, by tilting the vehicle to one side about 45 degrees, and keeping it like that. It should keep the same angle. If it drifts back, increase the I gain. A low I gain is also visible in a log, when there is an offset between the desired and the actual rate over a longer time.

Typical values are:

  • standard form (P = 1): between 0.5 (VTOL plane), 1 (500 size) and 8 (4" racer), for any value of K

  • parallel form (K = 1): between 0.3 and 0.5 if P is around 0.15 The pitch gain usually needs to be a bit higher than the roll gain.

Testing Procedure

To test the current gains, provide a fast step-input when hovering and observe how the vehicle reacts. It should immediately follow the command, and neither oscillate, nor overshoot (it feels 'locked-in').

You can create a step-input for example for roll, by quickly pushing the roll stick to one side, and then let it go back quickly (be aware that the stick will oscillate too if you just let go of it, because it is spring-loaded — a well-tuned vehicle will follow these oscillations).

:::note A well-tuned vehicle in Acro mode will not tilt randomly towards one side, but keeps the attitude for tens of seconds even without any corrections. :::

Logs

Looking at a log helps to evaluate tracking performance as well. Here is an example for good roll and yaw rate tracking:

Attitude Controller

This controls the orientation and outputs desired body rates with the following tuning parameters:

The attitude controller is much easier to tune. In fact, most of the time the defaults do not need to be changed at all.

To tune the attitude controller, fly in Manual/Stabilized mode and increase the P gains gradually. If you start to see oscillations or overshoots, the gains are too high.

The following parameters can also be adjusted. These determine the maximum rotation rates around all three axes:

Thrust Curve

The tuning above optimises performance around the hover throttle. But you may start to see oscillations when going towards full throttle.

:::note The rate controller might need to be re-tuned if you change this parameter. :::

The mapping from motor control signals (e.g. PWM) to expected thrust is linear by default — setting THR_MDL_FAC to 1 makes it quadratic. Values in between use a linear interpolation of the two. Typical values are between 0.3 and 0.5.

:::note The mapping between PWM and static thrust depends highly on the battery voltage. :::

An alternative way of performing this experiment is to make a scatter plot of the normalized motor command and thrust values, and iteratively tune the thrust curve by experimenting with the THR_MDL_FAC parameter. An example of that graph is shown here:

If raw motor command and thrust data is collected throughout the full-scale range in the experiment, you can normalize the data using the equation:

normalized_value = ( raw_value - min (raw_value) ) / ( max ( raw_value ) - min ( raw_value ) )

After you have a scatter plot of the normalized values, you can try and make the curve match by plotting the equation

rel_thrust = ( THR_MDL_FAC ) * rel_signal^2 + ( 1 - THR_MDL_FAC ) * rel_signal

In this example above, the curve seemed to fit best when THR_MDL_FAC was set to 0.7.

If you don't have access to a thrust stand, you can also tune the modeling factor empirically. Start off with 0.3 and increase it by 0.1 at a time. If it is too high, you will start to notice oscillations at lower throttle values. If it is too low you'll notice oscillations at higher throttle values.

Airmode & Mixer Saturation

The rate controller outputs torque commands for all three axis (roll, pitch and yaw) and a scalar thrust value, which need to be converted into individual motor thrust commands. This step is called mixing.

It can happen that one of the motor commands becomes negative, for example for a low thrust and large roll command (and similarly it can go above 100%). This is a mixer saturation. It is physically impossible for the vehicle to execute these commands (except for reversible motors). PX4 has two modes to resolve this:

  • Either by reducing the commanded torque for roll such that none of the motor commands is below zero (Airmode disabled). In the extreme case where the commanded thrust is zero, it means that no attitude correction is possible anymore, which is why a minimum thrust is always required for this mode.

  • Or by increasing (boosting) the commanded thrust, such that none of the motor commands is negative (Airmode enabled). This has the big advantage that the attitude/rates can be tracked correctly even at low or zero throttle. It generally improves the flight performance.

    However it increases the total thrust which can lead to situations where the vehicle continues to ascend even though the throttle is reduced to zero. For a well-tuned, correctly functioning vehicle it is not the case, but for example it can happen when the vehicle strongly oscillates due to too high P tuning gains.

Both modes are shown below with a 2D illustration for two motors and a torque command for roll r. On the left motor r is added to the commanded thrust, while on the right motor it is subtracted from it. The motor thrusts are in green. With Airmode enabled, the commanded thrust is increased by b. When it is disabled, r is reduced.

If mixing becomes saturated towards the upper bound the commanded thrust is reduced to ensure that no motor is commanded to deliver more than 100% thrust. This behaviour is similar to the Airmode logic, and is applied whether Airmode is enabled or disabled.

PX4 supports two (mathematically equivalent) forms of the PID rate controller in a single "mixed" implementation: and .

:::note The derivative term (D) is on the feedback path in order to avoid an effect known as the . :::

(www.controleng.com)

(Wikipedia) :::

Roll rate control (, , , )

Pitch rate control (, , , )

Yaw rate control (, , , )

The rate controller can be tuned in or :

And here is a good example for the roll rate tracking with several flips, which create an extreme step-input. You can see that the vehicle overshoots only by a very small amount:

Roll control ()

Pitch control ()

Yaw control ()

Maximum roll rate ()

Maximum pitch rate ()

Maximum yaw rate ()

To counteract that, adjust the thrust curve with the parameter.

If you have a (or can otherwise measure thrust and motor commands simultaneously), you can determine the relationship between the motor control signal and the motor's actual thrust, and fit a function to the data. The motor command in PX4 called actuator_output can be PWM, Dshot, UAVCAN commands for the respective ESCs in use. shows one way for how the thrust model factor THR_MDL_FAC may be calculated from previously measured thrust and PWM data. The curves shown in this plot are parametrized by both α and k, and also show thrust and PWM in real units (kgf and μs). In order to simplify the curve fit problem, you can normalize the data between 0 and 1 to find k without having to estimate α (α = 1, when the data is normalized).

]

over a linear range of normalized motor command values between 0 and 1. Note that this is the equation that is used in the firmware to map thrust and motor command, as shown in the parameter reference. Here, rel_thrust is the normalized thrust value between 0 and 1, and rel_signal is the normalized motor command signal value between 0 and 1.

Once your vehicle flies well you can enable Airmode via the parameter.

derivative kick
Not all PID controllers are the same
PID controller > Standard versus parallel (ideal) PID form
Acro mode
Manual/Stabilized mode
thrust stand
This Notebook
Parallel
Standard
Autotune
Position mode
airmode
thrust curve parameter
PID_Mixed
PID_Parallel
PID_Standard
roll rate tracking
yaw rate tracking
Graph showing relative thrust and PWM scatter
Airmode
roll rate tracking flips
Thrust Curve Compensation
SDLOG_PROFILE
MC_AIRMODE
MC_ROLLRATE_P
MC_ROLLRATE_I
MC_ROLLRATE_D
MC_ROLLRATE_K
MC_PITCHRATE_P
MC_PITCHRATE_I
MC_PITCHRATE_D
MC_PITCHRATE_K
MC_YAWRATE_P
MC_YAWRATE_I
MC_YAWRATE_D
MC_YAWRATE_K
MC_ROLL_P
MC_PITCH_P
MC_YAW_P
MC_ROLLRATE_MAX
MC_PITCHRATE_MAX
MC_YAWRATE_MAX
THR_MDL_FAC
THR_MDL_FAC
MC_AIRMODE