MAVLINKHUD

Overview

The PSC parameter group contains the PID Tuning parameters for the Position Controller. This library is the "brains" of the navigation system for multicopters and blimps.

While the ATC group handles how the drone rotates (Attitude), the PSC group handles how it moves through 3D space (Position and Velocity). It translates a waypoint target into the specific tilt angles and throttle levels needed to get there.

Key Concepts: The Cascaded Loop

Like attitude control, position control uses a cascaded structure:

1. Position Loop (Outer)

  • Input: Target Position (Lat/Lon/Alt) vs. Actual Position.
  • Output: Target Velocity (m/s).
  • Parameters: PSC_POSXY_P, PSC_POSZ_P.

2. Velocity Loop (Middle)

  • Input: Target Velocity vs. Actual Velocity (from EKF).
  • Output: Target Acceleration (m/s²).
  • Parameters: PSC_VELXY_P/I/D, PSC_VELZ_P/I/D.

3. Acceleration Loop (Inner)

  • Input: Target Acceleration vs. Actual Acceleration (from IMU).
  • Output: Desired Lean Angle (to ATC) and Throttle level.
  • Parameters: PSC_ACCZ_P/I/D (specifically for vertical control).

Key Parameters

  • PSC_POSXY_P: How aggressively the drone tries to close a horizontal position gap.
  • PSC_VELXY_P: Horizontal velocity responsiveness.
  • PSC_ACCZ_P/I/D: Vertical acceleration tuning. Critical for stable hover and smooth altitude changes.
  • PSC_JERK_XY: Smoothness of horizontal transitions (m/s/s/s).

Integration Guide

Tuning Altitude Hold

  1. If the drone "bounces" or "hunts" vertically while trying to hold altitude, your PSC_ACCZ_ gains are likely too high.
  2. If it feels "sloppy" and drops significantly when moving forward, increase PSC_ACCZ_I and PSC_POSZ_P.

Tuning Loiter

  1. If the drone overshoots its target and circles back (toilet-bowling), first check the compass. If compass is perfect, then reduce PSC_POSXY_P.

Developer Notes

  • Library: libraries/AC_PosControl.
  • Coordinates: Uses the NED (North-East-Down) frame for all internal calculations.

PSC_ACCZ_D

Default 0.0
Range 0.0 0.4

Position Control Acceleration (Vertical) D Gain (PSC_ACCZ_D)

Description

PSC_ACCZ_D is the vertical "shock absorber." It provides damping to the vertical movement by reacting to how fast the vertical acceleration is changing. It is primarily used to stop the drone from "ringing" or bouncing vertically when it hits its target altitude.

In many standard builds, this parameter is set to 0.0 because the air itself provides enough natural damping for the vertical axis. However, for high-performance or very large vehicles, a small amount of D-gain can significantly clean up vertical tracking.

  • Low Value (0.0): Standard vertical behavior. Relies on physics and P-gain for stabilization.
  • High Value: Stiffens the vertical response. Makes the drone feel "locked" to its height even in turbulent air.
  • Too High: Amplifies IMU noise and motor vibrations, causing the motors to "chirp" or heat up rapidly without any visible movement of the drone.

The Mathematics

This parameter scales the derivative of the acceleration error.

$$ \text{Throttle}{out} += k\_D \cdot \frac{d(\vec{A}{z\_error})}{dt} $$

Where:

  • $\vec{A}{z\_error} = \vec{A}{z\_target} - \vec{A}\_{z\_measured}$.
  • $k\_D$ is PSC_ACCZ_D.

Filter dependency: Just like the horizontal D-term, the vertical D-term is extremely sensitive to noise. It is heavily dependent on the PSC_ACCZ_FLTD filter to prevent motor damage.

The Engineer's View

This parameter is the _kd member of the _pid_accel_z object inside AC_PosControl.

It is executed in AC_PID::update_all():

// AC_PID.cpp
if (is_positive(dt)) {
    float derivative = (error - _last_error) / dt;
    _derivative = _last_derivative + (dt / (_filt_D_hz + dt)) * (derivative - _last_error) / dt;
}
return ... + _derivative * _kd;

Note that the derivative is filtered using a low-pass filter defined by PSC_ACCZ_FLTD. Without this filter, the D-term would be unusable due to the high vibration levels found in multirotors.

Tuning & Behavior

  • Default Value: 0.0
  • Range: 0.0 - 0.4
  • Effect of Increasing: Reduces vertical "bounce" at the end of a climb or descent. Better stability in ground effect.
  • Effect of Decreasing: Smoother, quieter motor operation.

Use Case Recommendations

  • Small High-Performance Drones: Increase to 0.05 - 0.1. Helps the drone stop exactly on its altitude target after aggressive maneuvers.
  • Heavy Lift / Cinematic: Keep at 0.0. Large props are slow to react; adding D-gain here usually just creates heat without improving tracking.
  • High Turbulence / High Wind: Increase to 0.1. Provides additional authority to fight vertical gusts.

Troubleshooting

  • Scenario: Vertical height hold is perfect, but motors sound "scratchy" or "grind-y" in Loiter.
    • Diagnosis: PSC_ACCZ_D is too high, amplifying IMU noise into the ESCs.
    • Fix: Set PSC_ACCZ_D to 0.0.

PSC_ACCZ_D_FF

Default 0.0
Range 0 0.02

Position Control Acceleration (Vertical) Derivative Feed-Forward (PSC_ACCZ_D_FF)

Description

PSC_ACCZ_D_FF is an advanced "predictive" term for vertical flight. While standard Feed-Forward (PSC_ACCZ_FF) looks at the target acceleration itself, the Derivative Feed-Forward (D_FF) looks at how fast the target is changing.

Think of it as the "lookahead" for a vertical punch. If the software suddenly requests a massive increase in acceleration, the D_FF term instantly adds a burst of throttle to help the motors overcome the inertia of the propellers. It helps the drone "lead" into a maneuver before any error has even occurred.

  • Low Value (0.0): Standard behavior. The drone accelerates as commanded by the shaper.
  • High Value: Creates a very aggressive vertical response. The drone "snaps" into climbs and descents.
  • Too High: Can cause "kickback" or jerky movements, as the drone over-predicts the needed force.

The Mathematics

The D_FF term is proportional to the derivative of the target signal ($A\_{z\_target}$):

$$ \text{Throttle}{D\_FF} = \frac{d(\vec{A}{z\_target})}{dt} \cdot k\_{D\_FF} $$

Where:

  • $k\_{D\_FF}$ is PSC_ACCZ_D_FF.
  • $\frac{d(\vec{A}\_{z\_target})}{dt}$ is the rate of change of the acceleration setpoint.

This is added to the final throttle sum alongside the P, I, D, and base FF terms.

The Engineer's View

This parameter maps to _kdff in the _pid_accel_z object.

It is executed in AC_PID::update_all():

// AC_PID.cpp
if (is_positive(dt)) {
    float target_derivative = (target - _last_target) / dt;
    _pid_info.D_FF = target_derivative * _kdff;
}

Because it looks at the target derivative, it is immune to IMU vibration noise (unlike the standard D-term). However, it is very sensitive to "steps" in the high-level path planner, which is why it's usually used with a well-shaped S-curve.

Tuning & Behavior

  • Default Value: 0.0
  • Range: 0.0 - 0.02
  • Effect of Increasing: Snappier, more instantaneous vertical transitions. Reduces altitude sag at the start of a climb.
  • Effect of Decreasing: Smoother, more organic vertical movement.

Use Case Recommendations

  • Acrobatic / FPV Autonomous Flight: Increase to 0.005. Helps the drone track aggressive 3D flight paths where altitude changes are frequent and sharp.
  • Standard Multirotors: Keep at 0.0. The standard shaper and P-gain are usually sufficient.
  • High-Speed Vertical Search: Increase to 0.01. If the drone is rapidly oscillating its height to search for an object, D_FF improves the accuracy of those transitions.

Troubleshooting

  • Scenario: Drone makes a distinct "pop" or "click" sound in the motors when starting a vertical movement.
    • Diagnosis: PSC_ACCZ_D_FF is likely too high, commanding an impossible step-change in motor torque.
    • Fix: Set back to 0.0.

PSC_ACCZ_FF

Default 0.0
Range 0 0.5

Position Control Acceleration (Vertical) Feed-Forward (PSC_ACCZ_FF)

Description

PSC_ACCZ_FF is the "prediction" component of the altitude controller. While the P, I, and D terms react to errors (mistakes the drone has already made), the Feed-Forward (FF) term reacts to the command itself.

If you tell the drone to climb at 2 m/s, the FF term instantly calculates a baseline throttle increase before the drone even starts to sink or slow down. It provides "pre-emptive authority," making the vertical control feel significantly more responsive and connected to the pilot's sticks.

  • Low Value (0.0): The drone relies entirely on error-correction. It will always lag slightly behind your climb/descent commands.
  • High Value: The drone "jumps" instantly when you command a climb.
  • Too High: The drone will "kick" violently and potentially overshoot its climb rate because it's adding too much power before the sensors can even measure the movement.

The Mathematics

The Feed-Forward term is multiplied directly by the target acceleration:

$$ \text{Throttle}{FF} = \vec{A}{z\_target} \cdot k\_{FF} $$

Where:

  • $\vec{A}\_{z\_target}$ is the requested acceleration.
  • $k\_{FF}$ is PSC_ACCZ_FF.

The total output becomes:
$$ \text{Throttle}{total} = \text{Throttle}{FF} + \text{Throttle}{P} + \text{Throttle}{I} + \text{Throttle}\_{D} $$

The Engineer's View

This parameter maps to _kff in the _pid_accel_z object.

It is applied in AC_PosControl::update_z_controller():

// AC_PosControl.cpp
thr_out = _pid_accel_z.update_all(_accel_target.z, z_accel_meas, _dt, ...) * 0.001f;
thr_out += _pid_accel_z.get_ff() * 0.001f;

In ArduPilot, Feed-Forward is often preferred over high P-gains because it does not create the same high-frequency oscillations. It is a "clean" way to get performance.

Tuning & Behavior

  • Default Value: 0.0 (Standard)
  • Range: 0.0 - 0.5
  • Effect of Increasing: Faster response to altitude commands. Reduces the "initial drop" when switching into AltHold/Loiter while moving fast.
  • Effect of Decreasing: Smoother, more damped vertical response.

Use Case Recommendations

  • Standard Build: Keep at 0.0. The vertical loop is usually strong enough without it.
  • High-Dynamics / Racing: Increase to 0.1 - 0.2. Gives the "vertical punch" needed to clear obstacles instantly.
  • Helicopters (Traditional): Keep at 0.0. Collective pitch response is different from multirotor RPM response; FF can cause over-speeding of the head.

Troubleshooting

  • Scenario: When you push the throttle stick up, the drone "twitches" or "kicks" up violently for a split second, then settles into a smooth climb.
    • Diagnosis: PSC_ACCZ_FF is too high. The initial "kick" from the command is overpowering the drone's inertia.
    • Fix: Reduce PSC_ACCZ_FF by 0.05.

PSC_ACCZ_FLTD

Hz
Default 0.0
Range 0 100

Position Control Acceleration (Vertical) D-Term Filter (PSC_ACCZ_FLTD)

Description

PSC_ACCZ_FLTD is the specific filter for the vertical Derivative (D) gain.

In the altitude controller, the D-gain (PSC_ACCZ_D) acts as a damper to stop the drone from bouncing. However, the derivative calculation (which looks at the rate of change) is extremely sensitive to motor vibration. Without a filter, even a tiny D-gain would amplify IMU noise so much that the motors would oscillate at hundreds of Hertz, potentially causing fire or mechanical failure.

  • Standard Build: If PSC_ACCZ_D is 0, this parameter does nothing.
  • High Performance: If you use D-gain to stabilize a heavy or high-power vehicle, you must set this filter to a sensible value (e.g. 10-20Hz).
  • Default (0): The filter is effectively disabled or follows the main error filter.

The Mathematics

The D-term calculates the derivative of the error, then passes it through this low-pass filter:

$$ \vec{D}{filtered} = \vec{D}{prev} + \alpha \cdot \left( \frac{d(\vec{A}{err})}{dt} - \vec{D}{prev} \right) $$

Where the filter coefficient $\alpha$ is calculated from PSC_ACCZ_FLTD ($f\_c$):

$$ \alpha = \frac{dt}{dt + \frac{1}{2\pi f\_c}} $$

The Engineer's View

This parameter maps to _filt_D_hz in the _pid_accel_z object.

It is applied in AC_PID::update_all():

// AC_PID.cpp
if (is_positive(dt)) {
    float derivative = (error - _last_error) / dt;
    _derivative = _last_derivative + (dt / (_filt_D_hz + dt)) * (derivative - _last_derivative);
}

The frequency is typically set lower than the main error filter because the derivative calculation inherently "creates" noise by looking at infinitesimal changes between samples.

Tuning & Behavior

  • Default Value: 0.0 Hz (Disabled/Auto)
  • Range: 0.0 - 100.0 Hz
  • Effect of Increasing: Allows the D-term to react faster to "thumps" or turbulence, but increases motor heating.
  • Effect of Decreasing: Smoother vertical behavior, but the D-term becomes less effective at stopping vertical bounces.

Use Case Recommendations

  • Most Multirotors: Keep at 0.0. Unless you are manually tuning PSC_ACCZ_D, this filter is not needed.
  • Heavy Industrial Drones: Set to 10.0 Hz (if using D-gain). Provides a clean signal for the damper to work without excites frame resonances.
  • Autonomous Landing on Ships/Moving Targets: Set to 20.0 Hz. Allows for the high-authority damping needed when the drone must "snap" to a height target as the platform moves beneath it.

Troubleshooting

  • Scenario: You increased PSC_ACCZ_D and now the motors are making a high-pitched "singing" noise.
    • Diagnosis: High-frequency derivative noise.
    • Fix: Decrease PSC_ACCZ_FLTD to 5.0 or 7.0 Hz.

PSC_ACCZ_FLTE

Hz
Default 20.0
Range 1 100

Position Control Acceleration (Vertical) Error Filter (PSC_ACCZ_FLTE)

Description

PSC_ACCZ_FLTE is the frontline defense against vertical vibrations. It filters the difference between the drone's target vertical acceleration and the actual acceleration measured by the IMU.

On most multirotors, the "Z-axis" is the noisiest. Propeller wash and motor imbalance create constant vertical vibration. If the innermost throttle controller (Acceleration loop) tried to track these vibrations, the motors would work overtime, wasting battery and potentially burning out. This filter ensures that only the "real" movements of the drone are passed into the throttle logic.

  • Higher Frequency (e.g. 40Hz): Faster throttle response to turbulence, but high risk of passing motor noise through.
  • Lower Frequency (e.g. 10Hz): Very smooth vertical hold, but the drone may feel "mushy" or slow to respond to heavy gusts.
  • Default (20Hz): A robust balance for 99% of multirotors.

The Mathematics

This is a single-pole low-pass filter:

$$ \vec{A}{err\_filtered} = \vec{A}{err\_prev} + \alpha \cdot (\vec{A}{err\_raw} - \vec{A}{err\_prev}) $$

Where $\alpha$ is derived from PSC_ACCZ_FLTE:

$$ \alpha = \frac{dt}{dt + \frac{1}{2\pi f\_c}} $$

Note: ArduPilot's innermost filters often run at the full loop rate (400Hz+), making them very effective at rejecting high-frequency noise.

The Engineer's View

This parameter maps to _filt_E_hz in the _pid_accel_z object.

It is applied in AC_PID::update_all():

// AC_PID.cpp
if (_reset_filter) {
    _reset_filter = false;
    _error = target - measurement;
} else {
    _error += ((target - measurement) - _error) * get_filt_E_alpha(dt);
}

The filtered _error is then used for the P, I, and D calculations.

Tuning & Behavior

  • Default Value: 20.0 Hz
  • Range: 1.0 - 100.0 Hz
  • Effect of Increasing: Faster vertical "clamping" to the target. Better for racing and aggressive maneuvering.
  • Effect of Decreasing: Quieter motors, less vibration-induced heating, but altitude hold may "sag" slightly during fast turns.

Use Case Recommendations

  • Small, High-Vibration Racers: Decrease to 10.0 - 15.0 Hz. Helps isolate the flight controller from the extreme noise generated by small, high-RPM motors.
  • Heavy Lift / Smooth Cinematic: Keep at 20.0 Hz. This provides plenty of responsiveness for smooth flight.
  • Large-Prop High-Inertia Drones (>22 inch): Decrease to 10.0 Hz. Slow props can't react to high frequencies anyway, so there is no benefit to a high filter cutoff.

Troubleshooting

  • Scenario: Drone makes a "grinding" or "growling" sound when hovering in AltHold, but is quiet in manual Stabilize mode.
    • Diagnosis: High vertical vibration is being amplified by the Acceleration loop.
    • Fix: Reduce PSC_ACCZ_FLTE to 10.0 Hz and check if the noise disappears.

PSC_ACCZ_FLTT

Hz
Default 0.0
Range 0 50

Position Control Acceleration (Vertical) Target Filter (PSC_ACCZ_FLTT)

Description

PSC_ACCZ_FLTT smooths the "command" signal before it reaches the vertical acceleration loop.

While other filters (like PSC_ACCZ_FLTE) deal with noise from the sensors, this filter deals with jumps in the code. Because the altitude controller is a cascade of loops, a sudden change in the target altitude (a "step" input) can result in a sudden jump in the requested acceleration. This filter rounds off those sharp edges, ensuring the motors increase their RPM smoothly rather than with a violent "kick."

  • Low Frequency (e.g. 5Hz): Very smooth vertical transitions. The drone "wafts" into its movements.
  • High Frequency (e.g. 40Hz): Immediate response to target changes. The drone reacts "instantly" to stick inputs.
  • Default (0): The filter is typically disabled or follows the main loop rate.

The Mathematics

This is a low-pass filter applied to the target acceleration ($\vec{A}\_{target}$):

$$ \vec{A}{target\_filtered} = \vec{A}{target\_prev} + \alpha \cdot (\vec{A}{target\_raw} - \vec{A}{target\_prev}) $$

Where $\alpha$ is derived from PSC_ACCZ_FLTT:

$$ \alpha = \frac{dt}{dt + \frac{1}{2\pi f\_c}} $$

Effect: This effectively acts as a "Time Constant" for the vertical command. A 10Hz filter means the command will reach 63% of its target value in about 16ms.

The Engineer's View

This parameter maps to _filt_T_hz in the _pid_accel_z object.

It is applied in AC_PID::update_all():

// AC_PID.cpp
_target += (target - _target) * get_filt_T_alpha(dt);

By filtering the target at the entry point of the innermost loop, ArduPilot ensures that the entire acceleration/throttle PID is protected from discontinuous jumps in the software's setpoints.

Tuning & Behavior

  • Default Value: 0.0 Hz (Disabled)
  • Range: 0.0 - 50.0 Hz
  • Effect of Increasing: Snappier, more "connected" feel to the throttle stick.
  • Effect of Decreasing: Smoother, more professional cinematic vertical movement.

Use Case Recommendations

  • Standard FPV / General Flying: Keep at 0.0. The existing kinematic shapers (PSC_JERK_Z) already provide excellent smoothing.
  • Smooth Cinematic Reveleals: Set to 5.0 Hz. Adds an extra layer of "organic" smoothness to any automated altitude changes.
  • Rescue / High-Speed Obstacle Avoidance: Keep at 0.0 or set >30Hz. You want the absolute minimum lag when the avoidance system commands a climb.

Troubleshooting

  • Scenario: Drone feels "disconnected" vertically; there is a noticeable lag between moving the throttle stick and the drone starting to climb.
    • Diagnosis: PSC_ACCZ_FLTT is likely set too low.
    • Fix: Increase to 20.0 Hz or set to 0.0.

PSC_ACCZ_I

Default 1.0
Range 0.0 3.0

Position Control Acceleration (Vertical) I Gain (PSC_ACCZ_I)

Description

PSC_ACCZ_I is the "gravity memory" of the drone. It works in the innermost vertical loop to ensure that the drone actually generates the required lift to stay level.

Its most important role is compensating for Hover Throttle. If you add a heavy camera to your drone, it now requires 60% throttle to hover instead of 50%. The I-term "notices" the persistent downward acceleration error and increases the baseline throttle until the drone stops sinking.

  • Low Value: The drone will sink significantly when you first switch to AltHold or Loiter. It may also sink during the end of a battery's life as voltage drops.
  • High Value: The drone adapts quickly to changes in weight or voltage.
  • Too High: The drone will "bounce" or "hunt" for the hover point, creating a slow vertical surge.

The Mathematics

This parameter scales the accumulation of vertical acceleration error.

$$ \text{Throttle}{out} += \int\_0^t (\vec{A}{z\_target} - \vec{A}\_{z\_measured}) \cdot k\_I \cdot dt $$

Where:

  • $\vec{A}{z\_target} - \vec{A}{z\_measured}$ is the instantaneous error in vertical force.
  • $k\_I$ is PSC_ACCZ_I.
  • Dimensionality: This gain converts Acceleration-Time into Throttle.

Anti-Windup: ArduPilot heavily limits the maximum value of this integrator via PSC_ACCZ_IMAX to ensure the drone doesn't full-throttle itself into space if it's held down on a table.

The Engineer's View

This parameter is the _ki member of the _pid_accel_z object inside AC_PosControl.

It is executed in AC_PID::update_all():

// AC_PID.cpp
_integrator += (_error * _ki) * dt;

A unique feature in ArduPilot is that this I-term is often pre-seeded (initialised) with the known MOT_THST_HOVER value during take-off to prevent the drone from "dropping" when it first transitions into an autonomous vertical mode.

Tuning & Behavior

  • Default Value: 1.0
  • Range: 0.0 - 3.0
  • Effect of Increasing: Faster adaptation to weight changes. More consistent hover height as the battery drains.
  • Effect of Decreasing: Smoother vertical behavior, but the drone will "sag" more under load.

Use Case Recommendations

  • Standard Build: Keep Default (1.0). This is robust for almost all vehicles.
  • Heavy Lift / Cargo (Variable Weight): Increase to 1.5. If you are dropping a payload, you want the drone to instantly "learn" its new lighter weight and not rocket upwards.
  • Low Power-to-Weight (Underpowered): Decrease to 0.5. Prevents the integrator from pushing the motors into saturation too quickly.

Troubleshooting

  • Scenario: Drone sinks for 2-3 seconds every time you switch to Loiter, then slowly climbs back to the right height.
    • Diagnosis: PSC_ACCZ_I is too low. It's taking too long to "learn" the gravity offset.
    • Fix: Increase PSC_ACCZ_I by 0.5.

PSC_ACCZ_IMAX

d%
Default 800
Range 0 1000

Position Control Acceleration (Vertical) I-Term Maximum (PSC_ACCZ_IMAX)

Description

PSC_ACCZ_IMAX is a critical safety limit for the vertical controller. It defines the maximum "authority" given to the vertical integrator (PSC_ACCZ_I).

The integrator's job is to learn the hover throttle. However, if the drone is physically prevented from climbing (e.g., it is tangled in a tree, or you are holding it down during a test), the integrator will keep increasing the throttle command to try and fix the error. Without a limit, the drone would eventually reach 100% throttle, leading to a dangerous situation if it suddenly breaks free.

  • Low Value: Limits the drone's ability to compensate for very heavy payloads or extremely low battery voltages.
  • High Value: Allows the drone to compensate for massive weight changes, but increases the risk of "runaway" throttle if the drone is stuck.
  • Units: Expressed in "Deci-percent" of throttle (e.g., 800 = 80%).

The Mathematics

The integrator ($\vec{I}$) is calculated over time, but is clamped by this parameter:

$$ \vec{I}{new} = \text{constrain}(\vec{I}{prev} + \text{error} \cdot k\_I \cdot dt, -\text{IMAX}, \text{IMAX}) $$

Where:

  • $\text{IMAX}$ is PSC_ACCZ_IMAX.
  • The output is typically scaled so that 1000 = full motor authority.

The Engineer's View

This parameter maps to _kimax in the _pid_accel_z object.

It is applied in AC_PID::update_all():

// AC_PID.cpp
_integrator = constrain_float(_integrator + (error * _ki * dt), -_kimax, _kimax);

ArduPilot also includes a Secondary Safety: the integrator is not allowed to increase if the motors are already at their physical limits (_motors.limit.throttle_upper), which further prevents windup.

Tuning & Behavior

  • Default Value: 800 (80% throttle authority)
  • Range: 0 - 1000
  • Effect of Increasing: Allows the drone to handle much heavier payloads than its "natural" hover point.
  • Effect of Decreasing: Safer for indoor testing; ensures the drone can't "power out" of a situation with more than a certain amount of force.

Use Case Recommendations

  • Standard Quad: Keep Default (800). This is safe and effective.
  • Heavy Lift / Delivery Drone: Increase to 1000 (if needed). If your payload is so heavy that you hover at 75% throttle, you need the full 1000 range to ensure the drone can still climb effectively.
  • Tethered Drone: Decrease to 400. If the drone is on a power-tether, you want to strictly limit how much it can pull on the cable if the sensors fail.

Troubleshooting

  • Scenario: Drone hovers perfectly at the start of the flight, but starts to sink slowly as the battery gets low, and never recovers.
    • Diagnosis: PSC_ACCZ_IMAX is too low. The drone needs more than 80% authority to stay level at low voltage, but the integrator is hitting the cap.
    • Fix: Increase PSC_ACCZ_IMAX to 1000.

PSC_ACCZ_NEF

Default 0
Range 1 8

Position Control Acceleration (Vertical) Error Notch Filter Index (PSC_ACCZ_NEF)

Description

PSC_ACCZ_NEF is an advanced "surgical" filter for altitude control. While standard filters (like PSC_ACCZ_FLTE) remove all high-frequency noise, a Notch Filter removes noise at one specific, problematic frequency (and its harmonics).

On many drones, the frame or the vertical column of air under the propellers has a "resonant frequency"—a specific speed where the whole drone starts to vibrate vertically. If the altitude controller "hears" this vibration and tries to correct it, it can lead to a feedback loop that destroys the drone. By setting this index, you tell the vertical controller to use one of your pre-configured Harmonic Notch filters (usually linked to motor RPM or an FFT) to specifically ignore that resonant vertical frequency.

  • Set to 0: No notch filter is applied to the vertical error.
  • Set to 1-8: Uses the corresponding Harmonic Notch filter (configured via INS_HNTCH_* parameters).

The Mathematics

The notch filter ($H\_{notch}$) is applied to the error signal ($E$) before it enters the PID logic:

$$ \vec{E}{clean} = H{notch}( \vec{A}{z\_target} - \vec{A}{z\_measured} ) $$

Where $H\_{notch}$ is a dynamic filter whose center frequency is typically driven by motor RPM ($f \propto RPM$):

$$ f\_{center} = \text{INS\_HNTCH\_FREQ} \cdot \frac{\text{RPM}}{\text{RPM}\_{ref}} $$

The Engineer's View

This parameter maps to _notch_E_filter in the _pid_accel_z object.

It is applied in AC_PID::update_all():

// AC_PID.cpp
if (_notch_E_filter > 0) {
    // Note: The actual filtering happens via a pointer to the 
    // INS harmonic notch library.
    error = _notch_E_filter_ptr->apply(error);
}

This integration allows the innermost altitude loop to benefit from the same advanced vibration rejection techniques used by the rate controllers (the main flight loops).

Tuning & Behavior

  • Default Value: 0 (Disabled)
  • Range: 1 - 8 (Filter Index)
  • Effect of Enabling: Significantly cleaner motor signals in Loiter. Allows for higher vertical P-gains (PSC_ACCZ_P) without causing vertical "chirp."
  • Effect of Disabling: More susceptible to vertical resonance and Z-axis motor noise.

Use Case Recommendations

  • Large Professional Drones: Set to 1 (usually). If you have already configured a Harmonic Notch for your main flight loops, applying it to the vertical loop is highly recommended to improve altitude hold performance in wind.
  • Small Racers: Keep at 0. Smaller drones usually have resonant frequencies high enough that a standard 20Hz low-pass filter is sufficient.
  • Coaxial / X8 Drones: Set to 1. Overlapping prop wash creates complex vertical resonances; the notch filter is often mandatory for a stable hover.

Troubleshooting

  • Scenario: Drone hovers well, but you see constant high-frequency oscillations in your PSCZ.Acc logs that match your motor RPM.
    • Diagnosis: Vertical resonance is passing into the altitude controller.
    • Fix: Ensure a Harmonic Notch is configured for the frame, and set PSC_ACCZ_NEF to that notch's index.

PSC_ACCZ_NTF

Default 0
Range 1 8

Position Control Acceleration (Vertical) Target Notch Filter Index (PSC_ACCZ_NTF)

Description

PSC_ACCZ_NTF is the sister filter to PSC_ACCZ_NEF. While the "Error Notch" filter cleans up noise from the sensors (IMU), the Target Notch filter cleans up noise from the commands (Software).

In a complex vertical control system, the "target acceleration" is often the result of many calculations—path planning, terrain following, and obstacle avoidance. Sometimes, these software processes can introduce rhythmic "stepping" or high-frequency ripples into the command signal. If these ripples happen to match the physical resonance of the frame or the motors, they can cause the drone to vibrate. This parameter allows the drone to specifically "ignore" those command-side frequencies.

  • Set to 0: No notch filter is applied to the vertical target.
  • Set to 1-8: Uses the corresponding Harmonic Notch filter (configured via INS_HNTCH_*).

The Mathematics

The notch filter ($H\_{notch}$) is applied to the target acceleration signal ($T$) before it enters the PID loop:

$$ \vec{T}{clean} = H{notch}( \vec{A}\_{z\_target\_raw} ) $$

The clean target $\vec{T}\_{clean}$ is then compared against the actual acceleration to compute the error.

The Engineer's View

This parameter maps to _notch_T_filter in the _pid_accel_z object.

It is applied in AC_PID::update_all():

// AC_PID.cpp
if (_notch_T_filter > 0) {
    target = _notch_T_filter_ptr->apply(target);
}

This is rarely used on standard multirotors but is critical for large, flexible frames or vehicles where the path planner (e.g., Terrain Following) might be updating at a lower rate than the PID loops, creating high-frequency "stairs" in the input signal.

Tuning & Behavior

  • Default Value: 0 (Disabled)
  • Range: 1 - 8 (Filter Index)
  • Effect of Enabling: Smoother motor sound during vertical maneuvers. Reduces "ringing" in the motor output when following complex vertical paths.
  • Effect of Disabling: Maximum responsiveness to command changes.

Use Case Recommendations

  • Terrain Following / Lidar-Based flight: Consider setting to 1. Lidar and terrain sensors often update at low frequencies (10-50Hz). This notch filter can round off the "jumps" in target altitude as the drone crosses uneven terrain.
  • Standard Build: Keep at 0. Standard low-pass filters (PSC_ACCZ_FLTT) are usually sufficient for command smoothing.
  • Very Large VTOL (Flexible Wings): Set to 1. Flexible wings can act like giant vertical springs. A command-side notch filter ensures the software never "kicks" the wing at its resonant frequency.

Troubleshooting

  • Scenario: Drone makes a distinct "thumping" or "humming" sound specifically when following terrain or a mission path, but is quiet when hovering still.
    • Diagnosis: Command-side resonance.
    • Fix: Apply a notch filter at the resonant frequency of the frame via PSC_ACCZ_NTF.

PSC_ACCZ_P

Default 0.5
Range 0.2 1.5

Position Control Acceleration (Vertical) P Gain (PSC_ACCZ_P)

Description

PSC_ACCZ_P is the innermost "knob" of the altitude control system. It determines how hard the flight controller pushes the motors to correct an error in Vertical Acceleration.

While PSC_POSZ_P cares about height and PSC_VELZ_P cares about climb speed, PSC_ACCZ_P cares about the instantaneous force required to counteract gravity and change speed. It effectively translates "I need more lift" into a specific motor PWM signal.

  • Low Value: The drone will feel "heavy" and slow to recover from drops. It may feel like it is struggling to stay airborne when carrying a heavy battery.
  • High Value: The drone will feel very "light" and responsive.
  • Too High: The drone will oscillate rapidly in the vertical axis, creating a "buzzing" sound as the motors rapidly oscillate their RPM.

The Mathematics

This parameter is the Proportional ($k\_P$) term in the Vertical Acceleration PID loop.

$$ \text{Throttle}{out} = k\_P \cdot (\vec{A}{z\_target} - \vec{A}\_{z\_measured}) + \dots + \text{Hover\_Throttle} $$

Where:

  • $\vec{A}\_{z\_target}$ is the acceleration required to reach the target climb rate.
  • $\vec{A}\_{z\_measured}$ is the vertical acceleration from the IMU (with gravity removed).
  • $k\_P$ is PSC_ACCZ_P.
  • Dimensionality: This gain converts Acceleration ($L T^{-2}$) into a dimensionless Throttle percentage ($0.0$ to $1.0$).

The Engineer's View

This parameter is the _kp member of the _pid_accel_z object (class AC_PID) inside AC_PosControl.

It is executed in AC_PosControl::update_z_controller():

// AC_PosControl.cpp
thr_out = _pid_accel_z.update_all(_accel_target.z, z_accel_meas, _dt, ...) * 0.001f;
thr_out += _motors.get_throttle_hover();

Note the * 0.001f scaling. This is because the internal PID library often calculates in larger units (e.g., centi-acceleration) and then scales back to the $0..1$ throttle range.

Tuning & Behavior

  • Default Value: 0.5
  • Range: 0.2 - 1.5
  • Effect of Increasing: Snappier recovery from vertical drops. Better tracking of the terrain in terrain-following modes.
  • Effect of Decreasing: Smoother, "softer" vertical behavior. Reduces vertical jitters in high-vibration environments.

Use Case Recommendations

  • Racing / Acro-Loiter: Increase to 0.7 - 0.9. Provides the high-authority lift needed for aggressive maneuvers.
  • Heavy Cargo Drone: Decrease to 0.3 - 0.4. Heavy vehicles have slow motor response times; pushing them too hard vertically with a high P-gain will lead to dangerous "vertical porpoising."
  • High Vibration Frames: Decrease to 0.3. High vibration creates noise in the IMU's Z-acceleration measurement. Reducing the P-gain prevents this noise from being amplified into the motors.

Troubleshooting

  • Scenario: Drone "bobs" up and down rapidly after a vertical punch.
    • Diagnosis: PSC_ACCZ_P is too high (P-gain oscillation).
    • Fix: Reduce PSC_ACCZ_P by 0.1 until the bobbing stops.

PSC_ACCZ_PDMX

d%
Default 0
Range 0 1000

Position Control Acceleration (Vertical) PD Maximum (PSC_ACCZ_PDMX)

Description

PSC_ACCZ_PDMX is a safety clamp for the "active" parts of the vertical controller. In a PID loop, the P and D terms are responsible for reacting to noise and sudden changes. If the drone is hit by a massive vertical gust, the P and D terms might compute a requested throttle change of 200%—which is physically impossible and can cause the control loop to behave erratically.

This parameter sets a ceiling on the combined power of P and D. It ensures that no matter how big the vertical error is, the immediate correction requested by the drone is kept within a reasonable range.

  • Low Value: Limits the drone's "snap" or ability to fight hard against turbulence.
  • High Value: Allows the drone to use its full motor power for immediate corrections.
  • Disabled (0): The PD sum is unlimited (limited only by the physical constraints of the motors).

The Mathematics

The P and D terms are summed and then constrained by this value:

$$ \text{PD}\_{output} = \text{constrain}(P + D, -\text{PDMX}, \text{PDMX}) $$

Where:

  • $P$ is the proportional contribution ($k\_P \cdot \text{error}$).
  • $D$ is the derivative contribution ($k\_D \cdot \frac{d}{dt}\text{error}$).
  • $\text{PDMX}$ is PSC_ACCZ_PDMX.

Note: This limit is applied before the Integral (I) term and Feed-Forward (FF) are added. This ensures that even if P and D are clamped, the drone can still achieve its full lift via the I-term.

The Engineer's View

This parameter maps to _kpdmax in the _pid_accel_z object.

It is applied in AC_PID::update_all():

// AC_PID.cpp
if (is_positive(_kpdmax)) {
    float pd_sum = P + D;
    pd_sum = constrain_float(pd_sum, -_kpdmax, _kpdmax);
    // ... use pd_sum ...
}

This is particularly useful in high-vibration environments where the D-term might otherwise produce extreme, unnecessary throttle spikes.

Tuning & Behavior

  • Default Value: 0 (Unlimited)
  • Range: 0 - 1000 (0 to 100% throttle authority)
  • Effect of Increasing: Increases the drone's ability to "punch" out of a vertical drop.
  • Effect of Decreasing: Makes the altitude hold safer and smoother, but less capable of handling extreme vertical wind.

Use Case Recommendations

  • Standard Drone: Keep at 0. Most modern builds don't need this clamp.
  • Large-Scale VTOL / Passenger Drones: Set to 500 (50%). Ensures that no software glitch or sensor spike can command more than half-throttle correction instantly, providing a smoother ride.
  • Indoor / Research Drones: Set to 300 (30%). A safe setting for testing new code where you want to limit how much the drone can "jump" if a sensor fails.

Troubleshooting

  • Scenario: Drone is very slow to recover from a vertical drop, even though PSC_ACCZ_P is high.
    • Diagnosis: PSC_ACCZ_PDMX might be set too low, capping the controller's authority.
    • Fix: Increase PSC_ACCZ_PDMX or set it to 0.

PSC_ACCZ_SMAX

Default 0.0
Range 0 200

Position Control Acceleration (Vertical) Slew Rate Limit (PSC_ACCZ_SMAX)

Description

PSC_ACCZ_SMAX is a protection mechanism for your motors and frame. A Slew Rate is a limit on how fast a signal can change over time.

If the vertical acceleration loop commands 10% throttle now and 90% throttle in the very next millisecond (due to noise or a sudden correction), the motors will try to accelerate violently. This causes massive current spikes and can actually shake the drone's frame apart. This parameter rounds off those sudden spikes, ensuring that the motor command always changes at a physically safe rate.

  • Low Value: Flight feels extremely soft and "buttery." The motors will sound very quiet.
  • High Value: Allows the motors to reach their target power as fast as they physically can.
  • Too High: Risk of "motor shrieking" and ESC damage due to extreme current transients.
  • Disabled (0): The software does not limit the rate of change of the motor command.

The Mathematics

The slew limit acts as a "speed limit" for the change in the PID output ($\Delta O$):

$$ |O\_{new} - O\_{prev}| \leq SMAX \cdot dt $$

If the calculated change in output exceeds $SMAX$, ArduPilot automatically reduces the P and D gains of the acceleration loop for that specific cycle to keep the output within the limit:

$$ \text{Scale Factor} = \frac{SMAX}{|P + D|\_{rate}} $$

The Engineer's View

This parameter maps to _slew_rate_max in the _pid_accel_z object.

It is executed in AC_PID::update_all():

// AC_PID.cpp
if (is_positive(_slew_rate_max)) {
    _pid_info.slew_rate = (P + D - _last_out_pd) / dt;
    if (fabsf(_pid_info.slew_rate) > _slew_rate_max) {
        // Reduce gains to meet the slew rate
        float gain_reduction = _slew_rate_max / fabsf(_pid_info.slew_rate);
        // ... apply reduction ...
    }
}

This is a dynamic gain reduction strategy. Instead of just clipping the output (which creates lag), it softens the controller until the "jerkiness" is gone.

Tuning & Behavior

  • Default Value: 0.0 (Disabled)
  • Range: 0 - 200
  • Effect of Increasing: Snappier, more immediate vertical control authority.
  • Effect of Decreasing: Smoother motor response, longer motor life, and potentially less "jello" in the camera feed.

Use Case Recommendations

  • Standard Build: Keep at 0.0. Modern ESCs and frames are usually strong enough to handle raw PID output.
  • Large Professional Drones (>10kg): Set to 50 - 100. Large drones have massive rotating inertia; trying to change their motor speed instantly is inefficient and stresses the ESCs.
  • Passenger-Carrying / Large VTOL: Set to 20. Safety and comfort are paramount; violent motor changes must be prevented by the software.

Troubleshooting

  • Scenario: Motors are making a "crunchy" or "scratchy" sound during fast descents.
    • Diagnosis: High-frequency PID chatter is creating excessive slew rates.
    • Fix: Set PSC_ACCZ_SMAX to 100 and check if the sound cleans up.

PSC_ANGLE_MAX

cdeg
Default 0
Range 0 4500

Position Control Angle Max (PSC_ANGLE_MAX)

Description

The PSC_ANGLE_MAX parameter serves as a safety governor for autonomous flight. It strictly limits how far the drone can tilt (lean) when it is flying itself (Loiter, Auto, Guided, RTL).

By default (0), it inherits the global ANGLE_MAX setting (typically 30-45 degrees), which applies to manual flight (Stabilize/AltHold). However, you often want autonomous modes to be gentler than manual modes. This parameter allows you to cap the auto-flight tilt to a lower value (e.g., 20 degrees) for smoother video or passenger comfort, while keeping the full range available for manual recovery.

  • Set to 0: Disabled. Uses ANGLE_MAX.
  • Set > 0: Overrides ANGLE_MAX for Position Control modes.

The Mathematics

The logic uses a ternary selector:

$$ \theta\_{limit} = \begin{cases} \text{PSC\_ANGLE\_MAX}, & \text{if } \text{PSC\_ANGLE\_MAX} > 0 \ \text{ANGLE\_MAX}, & \text{otherwise} \end{cases} $$

Where $\theta\_{limit}$ is the maximum centi-degrees of roll or pitch allowed.

The Engineer's View

This parameter corresponds to _lean_angle_max in AC_PosControl.

The logic is explicitly defined in AC_PosControl::get_lean_angle_max_cd():

// AC_PosControl.cpp
float AC_PosControl::get_lean_angle_max_cd() const
{
    if (is_positive(_angle_max_override_cd)) {
        return _angle_max_override_cd;
    }
    if (!is_positive(_lean_angle_max)) {
        return _attitude_control.lean_angle_max_cd(); // Returns global ANGLE_MAX
    }
    return _lean_angle_max * 100.0f;
}

This limit is applied at the very end of the update_xy_controller() loop to clip the requested acceleration.

Tuning & Behavior

  • Default Value: 0 (Inherit Global)
  • Range: 0 - 4500 (0 to 45 degrees)
  • Effect of Increasing: Allows the drone to fly faster in Auto/Loiter (since speed comes from tilt).
  • Effect of Decreasing: Limits top speed and acceleration. Makes flight smoother but reduces wind resistance.

Use Case Recommendations

  • Cinematography: Set to 1500 - 2000 (15-20 deg).
    • Why: Ensures the drone never tilts aggressively, keeping the landing gear out of the shot and the horizon stable.
  • High Wind Operations: Set to 0 (or >3000).
    • Why: If you cap this too low (e.g., 10 degrees) and the wind requires a 12-degree lean to hold position, the drone will be blown away (Fly-away risk).
  • General: Keep Default (0).

PSC_D_ACC_D

null
Default 0
Range null

PID Derivative Gain

Note: This parameter functions identically to PSC_ACCZ_D.

PSC_D_ACC_D_FF

null
Default 0
Range null

FF FeedForward Gain

Note: This parameter functions identically to PSC_ACCZ_D_FF.

PSC_D_ACC_FF

null
Default 0
Range null

FF FeedForward Gain

Note: This parameter functions identically to PSC_ACCZ_FF.

PSC_D_ACC_FLTD

Hz
Default AC_PID_DFILT_HZ_DEFAULT
Range null

PID D term filter frequency in Hz

Note: This parameter functions identically to PSC_ACCZ_FLTD.

PSC_D_ACC_FLTE

Hz
Default AC_PID_EFILT_HZ_DEFAULT
Range null

PID Error filter frequency in Hz

Note: This parameter functions identically to PSC_ACCZ_FLTE.

PSC_D_ACC_FLTT

Hz
Default AC_PID_TFILT_HZ_DEFAULT
Range null

PID Target filter frequency in Hz

Note: This parameter functions identically to PSC_ACCZ_FLTT.

PSC_D_ACC_I

null
Default 0
Range null

PID Integral Gain

Note: This parameter functions identically to PSC_ACCZ_I.

PSC_D_ACC_IMAX

null
Default 0
Range null

PID Integral Maximum

Note: This parameter functions identically to PSC_ACCZ_IMAX.

PSC_D_ACC_NEF

null
Default 0
Range 1 8

PID Error notch filter index

Note: This parameter functions identically to PSC_ACCZ_NEF.

PSC_D_ACC_NTF

null
Default 0
Range 1 8

PID Target notch filter index

Note: This parameter functions identically to PSC_ACCZ_NTF.

PSC_D_ACC_P

null
Default 0
Range null

PID Proportional Gain

Note: This parameter functions identically to PSC_ACCZ_P.

PSC_D_ACC_PDMX

null
Default 0
Range null

PD sum maximum

Note: This parameter functions identically to PSC_ACCZ_PDMX.

PSC_D_ACC_SMAX

null
Default 0
Range 0 200

Slew rate limit (PSC_D_ACC_SMAX)

Note: This parameter functions identically to PSC_ACCZ_SMAX.

PSC_D_POS_P

null
Default 0
Range null

PID Proportional Gain

Note: This parameter functions identically to PSC_POSZ_P.

PSC_D_VEL_D

null
Default 0
Range null

PID Derivative Gain

Note: This parameter functions identically to PSC_VELZ_D.

PSC_D_VEL_FF

null
Default 0
Range null

FF FeedForward Gain

Note: This parameter functions identically to PSC_VELZ_FF.

PSC_D_VEL_FLTD

Hz
Default AC_PID_DFILT_HZ_DEFAULT
Range null

PID D term filter frequency in Hz

Note: This parameter functions identically to PSC_VELZ_FLTD.

PSC_D_VEL_FLTE

Hz
Default AC_PID_EFILT_HZ_DEFAULT
Range null

PID Error filter frequency in Hz

Note: This parameter functions identically to PSC_VELZ_FLTE.

PSC_D_VEL_I

null
Default 0
Range null

PID Integral Gain

Note: This parameter functions identically to PSC_VELZ_I.

PSC_D_VEL_IMAX

null
Default 0
Range null

PID Integral Maximum

Note: This parameter functions identically to PSC_VELZ_IMAX.

PSC_D_VEL_P

null
Default 0
Range null

PID Proportional Gain

Note: This parameter functions identically to PSC_VELZ_P.

PSC_JERK_D

$m/s^3$
Default 5.0
Range 5.0 50.0

Position Control Jerk (Down/Vertical) (PSC_JERK_D)

Description

PSC_JERK_D is a common alias (often used in documentation and older Ground Control Stations) for the PSC_JERK_Z parameter. It controls the "smoothness" of vertical transitions (takeoff, landing, and climb/descent starts).

For full details on how this parameter affects flight dynamics and for tuning advice, please refer to the primary documentation page:

Click here for PSC_JERK_Z Documentation

The Mathematics

Identical to PSC_JERK_Z. It defines the third derivative of vertical position:
$$ j\_z = \frac{d^3z}{dt^3} $$

The Engineer's View

In modern ArduPilot C++ source code, this maps to _shaping_jerk_z within the AC_PosControl class. While older parameter systems may have used the "D" (Down) suffix for the NEU (North East Up) coordinate frame's vertical axis, modern versions standardize on "Z".

PSC_JERK_XY

$m/s^3$
Default 5.0
Range 1.0 20.0

Position Control Jerk XY (PSC_JERK_XY)

Description

PSC_JERK_XY defines the "smoothness" of the drone's horizontal movements. In physics, Jerk is the rate at which acceleration changes. High jerk means the drone snaps into a lean instantly; low jerk means it rolls into the lean gracefully.

ArduPilot uses S-Curve Kinematics to generate paths. Instead of jerky, "bang-bang" movements, the controller shapes the velocity profile so that acceleration and deceleration are applied gradually, respecting this Jerk limit.

  • Low Value: Flight feels very "fluid" and "soft." Ideal for cinematography.
  • High Value: Flight feels "robotic" and "snappy." The drone stops and starts with minimal lag.
  • Too High: Can cause mechanical stress or "ringing" (oscillation) as the motors try to change the vehicle's attitude faster than is physically possible.

The Mathematics

Jerk ($j$) is the third derivative of position ($p$):

$$ j(t) = \frac{d\vec{A}}{dt} = \frac{d^3\vec{P}}{dt^3} $$

In the ArduPilot shaper, this parameter limits the slope of the acceleration curve:

$$ |\vec{A}{target}(t) - \vec{A}{target}(t-dt)| \leq j\_{limit} \cdot dt $$

Where $j\_{limit}$ is PSC_JERK_XY.

The Engineer's View

This parameter is the _shaping_jerk_xy member in AC_PosControl.

It is used in AC_PosControl::set_max_speed_accel_xy() to initialize the kinematic path generators:

// AC_PosControl.cpp
_jerk_max_xy_cmsss = _shaping_jerk_xy * 100.0;

Crucially, the code includes a Safety Override: it will automatically lower your jerk limit if the Attitude Controller's maximum angular rates (ATC_RAT_RLL_P etc.) are too low to support the requested snap. It ensures the position controller doesn't "ask" for a lean faster than the drone can rotate.

Tuning & Behavior

  • Default Value: 5.0 m/s³
  • Range: 1.0 - 20.0 m/s³
  • Effect of Increasing: Snappier response to stick inputs in Loiter. Tighter cornering in Auto missions.
  • Effect of Decreasing: Smoother, "lazier" movement. Great for reducing "jello" in video.

Use Case Recommendations

  • Cinematic Drone: Decrease to 1.0 - 2.5. Creates beautiful, smooth transitions between hover and flight.
  • Industrial / Delivery: Keep Default (5.0). Good balance of speed and mechanical preservation.
  • Racing / Aggressive Auto: Increase to 10.0 - 15.0. Necessary for high-speed obstacle avoidance where every millisecond of acceleration counts.

Troubleshooting

  • Scenario: Drone "bobs" or "overshoots" slightly when stopping, despite high D-gain.
    • Diagnosis: PSC_JERK_XY might be too low, preventing the drone from applying brakes fast enough.
    • Fix: Increase PSC_JERK_XY in increments of 1.0.

PSC_JERK_Z

$m/s^3$
Default 5.0
Range 5.0 50.0

Position Control Jerk Z (Vertical) (PSC_JERK_Z)

Description

PSC_JERK_Z defines the vertical "acceleration ramp." It limits how quickly the drone can change its vertical acceleration.

In simple terms, it prevents the drone from "punching" the throttle or "slamming" the brakes when changing altitude. A high jerk value allows the drone to reach its target climb rate instantly, while a low value makes it "float" into the climb.

  • Low Value: Altitude changes feel very smooth and gentle. The drone "glides" into a stop. Ideal for cinematography or passenger-carrying vehicles.
  • High Value: The drone is very responsive to height changes. It stops exactly on the target line with no hesitation.
  • Too High: Can cause mechanical stress on the frame and battery, and potentially lead to vertical "ringing" as the motors try to achieve physically impossible acceleration rates.

The Mathematics

Vertical Jerk ($j\_z$) is the rate of change of vertical acceleration ($a\_z$):

$$ j\_z(t) = \frac{da\_z}{dt} = \frac{d^3z}{dt^3} $$

The ArduPilot shaper ensures that:

$$ |\vec{A}{z\_target}(t) - \vec{A}{z\_target}(t-dt)| \leq j\_{z\_limit} \cdot dt $$

Where $j\_{z\_limit}$ is PSC_JERK_Z.

The Engineer's View

This parameter is the _shaping_jerk_z member in AC_PosControl.

It is used in AC_PosControl::set_max_speed_accel_z() to initialize the vertical shaper:

// AC_PosControl.cpp
_jerk_max_z_cmsss = _shaping_jerk_z * 100.0;

The shaper is applied in AC_PosControl::input_pos_vel_accel_z(), where the commanded altitude is transformed into a kinematically consistent target that the drone's motors can actually follow.

Tuning & Behavior

  • Default Value: 5.0 m/s³
  • Range: 5.0 - 50.0 m/s³
  • Effect of Increasing: Snappier takeoff and landing. More aggressive response to altitude stick (throttle).
  • Effect of Decreasing: Smoother, "softer" vertical movement. Great for reducing camera gimbal "bob" during climb-out.

Use Case Recommendations

  • Cinematography: Keep Default (5.0) or decrease to 2.5. Standard 5.0 is already quite smooth, but for very slow cinematic reveals, lower is better.
  • Autonomous Landing (Precision): Increase to 10.0 - 15.0. When landing on a small target or a moving platform, you want the altitude controller to be extremely responsive to avoid "drifting" during the touchdown phase.
  • Industrial Inspection: Increase to 10.0. Allows the drone to maintain a consistent distance from a structure (e.g., wind turbine blade) even in gusty vertical air.

Troubleshooting

  • Scenario: Drone "over-accelerates" vertically when the throttle stick is moved small amounts, making fine altitude adjustments difficult.
    • Diagnosis: PSC_JERK_Z might be too high for the vehicle's thrust-to-weight ratio.
    • Fix: Reduce PSC_JERK_Z to 5.0 or 2.5.

PSC_NE_POS_P

null
Default 0
Range null

PID Proportional Gain

Note: This parameter functions identically to PSC_POSXY_P.

PSC_NE_VEL_D

null
Default 0
Range null

PID Derivative Gain

Note: This parameter functions identically to PSC_VELXY_D.

PSC_NE_VEL_FF

null
Default 0
Range null

FF FeedForward Gain

Note: This parameter functions identically to PSC_VELXY_FF.

PSC_NE_VEL_FLTD

Hz
Default AC_PID_DFILT_HZ_DEFAULT
Range null

PID D term filter frequency in Hz

Note: This parameter functions identically to PSC_VELXY_FLTD.

PSC_NE_VEL_FLTE

Hz
Default AC_PID_EFILT_HZ_DEFAULT
Range null

PID Error filter frequency in Hz

Note: This parameter functions identically to PSC_VELXY_FLTE.

PSC_NE_VEL_I

null
Default 0
Range null

PID Integral Gain

Note: This parameter functions identically to PSC_VELXY_I.

PSC_NE_VEL_IMAX

null
Default 0
Range null

PID Integral Maximum

Note: This parameter functions identically to PSC_VELXY_IMAX.

PSC_NE_VEL_P

null
Default 0
Range null

PID Proportional Gain

Note: This parameter functions identically to PSC_VELXY_P.

PSC_POSXY_P

Default 1.0
Range 0.5 2.0

Position Control (XY) P Gain (PSC_POSXY_P)

Description

The PSC_POSXY_P parameter determines the "stiffness" of the vehicle's position hold in the horizontal (XY) plane. It acts as the primary driver for converting position errors (how far you are from the target) into requested velocities (how fast you should fly to get back).

  • Low Value: The drone feels "loose" and will drift further from the target before correcting. It may feel sluggish to stop.
  • High Value: The drone fights aggressively to hold position. It stops sharply.
  • Too High: The drone will overshoot the target and oscillate (jitter) around the position hold, often observed as a rapid "twitching" in Loiter mode.

The Mathematics

This parameter is the Proportional ($k\_P$) term in the outer loop of the cascaded position controller.

$$ \vec{V}{target} = k\_P \cdot (\vec{P}{target} - \vec{P}\_{current}) $$

Where:

  • $\vec{V}\_{target}$ is the requested velocity (in cm/s) sent to the inner Velocity Loop.
  • $\vec{P}\_{target}$ is the desired location (e.g., where the sticks are commanded or the loiter point).
  • $\vec{P}\_{current}$ is the EKF estimated position.
  • $k\_P$ is the PSC_POSXY_P gain.
  • Dimensionality: Since it converts Position ($L$) to Velocity ($L T^{-1}$), the unit of $k\_P$ is $1/s$ (Hertz).

The Engineer's View

This parameter is an instance of the AC_P_2D class, instantiated as _p_pos_xy within the AC_PosControl library.

It is executed on every main loop cycle (typically 400Hz) inside AC_PosControl::update_xy_controller():

// AC_PosControl.cpp
Vector2f vel_target = _p_pos_xy.update_all(_pos_target.x, _pos_target.y, comb_pos);

The output of this P-controller becomes the input target for the Velocity PID loop (PSC_VELXY_*), meaning any noise or oscillation here will cascade down into the velocity and acceleration controllers.

Tuning & Behavior

  • Default Value: 1.0 (Standard for most quadcopters)
  • Range: 0.5 - 2.0
  • Effect of Increasing: Sharper position holding, faster braking when sticks are released.
  • Effect of Decreasing: Smoother braking, "softer" loiter, less aggressive correction against wind gusts.
  • Dependencies: If you change this significantly, you may need to re-tune PSC_VELXY_P and PSC_VELXY_D to handle the more aggressive velocity demands.

Use Case Recommendations

  • Cinematography: Decrease to 0.7 - 0.8.
    • Why: Prevents the "hard stop" when you release the sticks at a waypoint. It creates a gentle, coasting deceleration that looks more organic on camera.
  • Precision Inspection / Survey: Increase to 1.2 - 1.5.
    • Why: When inspecting a wind turbine or bridge, you want the drone to hold its coordinate exactly against wind gusts, even if the motor response is aggressive.
  • General Flying: Keep Default (1.0).
    • Why: Provides a balanced feel where the drone is responsive but not twitchy.

Practical Tuning Tip

For large, heavy cinematic drones, reduce this to 0.8 or 0.7 to prevent sudden jerky stops that ruin camera footage. For FPV racing or aggressive autonomous missions, increase to 1.2 - 1.5 for tight cornering accuracy.

PSC_POSZ_P

Default 1.0
Range 1.0 3.0

Position Control (Vertical) P Gain (PSC_POSZ_P)

Description

The PSC_POSZ_P parameter controls the "springiness" of the drone's altitude hold. It defines how aggressively the drone attempts to correct its height when it notices it is above or below its target altitude.

  • Low Value: The drone will feel "lazy" vertically. If you push it down, it will drift back up very slowly. It may sag when flying forward at speed.
  • High Value: The drone fights hard to maintain its altitude. It reacts instantly to small changes in height.
  • Too High: The drone will start to bounce or oscillate vertically (up and down) as it over-corrects small pressure sensor errors.

The Mathematics

This parameter is the Proportional ($k\_P$) term in the outer Altitude loop.

$$ V\_{z\_target} = k\_P \cdot (Z\_{target} - Z\_{current}) $$

Where:

  • $V\_{z\_target}$ is the requested climb/descent rate (in cm/s) passed to the inner Velocity Loop.
  • $Z\_{target}$ is the desired altitude (Barometer or Rangefinder).
  • $Z\_{current}$ is the EKF estimated altitude.
  • $k\_P$ is PSC_POSZ_P.
  • Dimensionality: Since it converts Altitude ($L$) to Velocity ($L T^{-1}$), the unit of $k\_P$ is $1/s$ (Hertz).

Example: If the drone is 1 meter (100cm) below its target and PSC_POSZ_P is 1.0, it will command a 100 cm/s climb rate. If you increase it to 2.0, it will command 200 cm/s for the same error.

The Engineer's View

This parameter is an instance of AC_P_1D (member _p_pos_z) within AC_PosControl.

It is executed in AC_PosControl::update_z_controller():

// AC_PosControl.cpp
_vel_target.z = _p_pos_z.update_all(pos_target_zf, _inav.get_position_z_up_cm());

The climb rate output is then capped by PILOT_SPEED_UP and PILOT_SPEED_DN before being sent to the Velocity PID loop.

Tuning & Behavior

  • Default Value: 1.0 (Standard)
  • Range: 1.0 - 3.0
  • Effect of Increasing: Faster return to target altitude. "Locked-in" feel.
  • Effect of Decreasing: Smoother altitude transitions. More forgiving of sensor noise (Baro drift).

Use Case Recommendations

  • Cinematography: Keep Default (1.0). Standard 1.0 provides a natural, smooth altitude hold that isn't robotic or jerky.
  • Terrain Following (Low Altitude): Increase to 1.5 - 2.0. When flying close to the ground using a rangefinder, you want the drone to follow the contours of the earth precisely. A higher P-gain ensures it doesn't "crash" into a hill because it was too slow to climb.
  • Heavy Lift / Tethered: Decrease to 0.8. Reduces the chance of vertical oscillations if the drone is physically constrained by a cable or heavy payload.

Troubleshooting

  • Scenario: Drone "bounces" up and down slowly in Loiter.
    • Diagnosis: PSC_POSZ_P is too high, creating a resonant oscillation with the landing throttle.
    • Fix: Reduce PSC_POSZ_P in steps of 0.2.

PSC_VELXY_D

Default 0.5
Range 0.0 1.0

Position Control Velocity (XY) D Gain (PSC_VELXY_D)

Description

The PSC_VELXY_D parameter provides Damping to the velocity controller. It reacts to the rate of change of the error. If the drone is rapidly approaching the target velocity, the D-term counter-acts the P-term to slow down the reaction, preventing it from shooting past the target.

Think of it as the shock absorbers on a car. Without them (D=0), the car bounces (oscillates) after a bump. With them, it settles quickly.

  • Too Low: The drone may overshoot the target velocity and "wobble" before settling.
  • Too High: The drone amplifies sensor noise (vibrations), causing rapid, high-frequency twitching in the motors and potentially overheating them.

The Mathematics

This parameter scales the filtered derivative of the error.

$$ \vec{A}{target} += k\_D \cdot \text{Filter}\left( \frac{d(\vec{V}{error})}{dt} \right) $$

Where:

  • $\frac{d(\vec{V}\_{error})}{dt}$ is the rate of change of the velocity error.
  • $\text{Filter}(\dots)$ is a low-pass filter (set by PSC_VELXY_FLTD) to remove high-frequency noise.
  • $k\_D$ is PSC_VELXY_D.

Significance: The D-term opposes rapid changes. If the error is decreasing quickly (you are fixing the problem), the derivative is negative, so the D-term subtracts from the output, "braking" the correction to prevent overshoot.

The Engineer's View

This parameter is the _kd member of the _pid_vel_xy object in AC_PosControl.

It is executed in AC_PID_2D::update_all():

// AC_PID_2D.cpp
if (is_positive(dt)) {
    const Vector2f derivative{(_error - error_last) / dt};
    _derivative += (derivative - _derivative) * get_filt_D_alpha(dt);
}
// ...
return ... + _derivative * _kd ...;

The derivative calculation relies on a clean dt (time step) and is heavily dependent on the input filter frequency (PSC_VELXY_FLTD) to be usable on a real flying vehicle.

Tuning & Behavior

  • Default Value: 0.5 (Standard Copter)
  • Range: 0.0 - 1.0
  • Effect of Increasing: Reduces overshoot, makes stops look "crisper" and more robotic. Increases susceptibility to vibration noise.
  • Effect of Decreasing: Softer stops, potential for "bounce-back" or low-frequency wobble.

Use Case Recommendations

  • Large Propellers (>15 inch): Decrease to 0.1 - 0.3.
    • Why: Large props have high inertia and slow response times. A high D-term tries to force rapid changes they can't physically achieve, leading to motor overheating.
  • Small Racers (<5 inch): Increase to 0.6 - 0.8.
    • Why: Low inertia allows for rapid response; high D-term locks the velocity in "on rails".
  • General: Keep Default (0.5).

Practical Tuning Tip

Tune P first until you see oscillation, then increase D to dampen it. If you hear a high-pitched grinding sound from the motors (noise amplification), reduce D immediately.

PSC_VELXY_FF

Default 0.0
Range 0 6.0

Position Control Velocity (XY) Feed-Forward (PSC_VELXY_FF)

Description

PSC_VELXY_FF is the "predictive throttle" for horizontal movement. While the P, I, and D terms react to mistakes (e.g., "I'm not flying as fast as I should be"), the Feed-Forward (FF) term reacts to the goal (e.g., "The pilot wants to fly at 5 m/s, so I need to lean by 10 degrees now").

By bypassing the error-correction loop, the FF term eliminates the "lag" associated with PID controllers. It allows the drone to start leaning the moment the stick is moved, rather than waiting for a velocity error to build up. This is the difference between a drone that "oozes" into movement and one that "snaps" into movement.

  • Low Value (0.0): Standard behavior. The drone relies on error-correction. There will be a slight delay between stick movement and the drone reaching target speed.
  • High Value: The drone leans instantly and aggressively.
  • Too High: The drone will "over-lean" when you first move the stick, causing it to shoot past the target speed and then jerk back.

The Mathematics

The Feed-Forward term is a direct multiplier of the desired velocity:

$$ \vec{A}{target\_FF} = \vec{V}{desired} \cdot k\_{FF} $$

Where:

  • $\vec{V}\_{desired}$ is the speed requested by the pilot or the Position loop.
  • $k\_{FF}$ is PSC_VELXY_FF.

The output is an acceleration ($\text{cm/s}^2$), which is directly converted into a target Roll and Pitch angle.

The Engineer's View

This parameter maps to _kff in the _pid_vel_xy object.

It is applied in AC_PID_2D::update_all():

// AC_PID_2D.cpp
_pid_info_x.FF = _target.x * _kff;
_pid_info_y.FF = _target.y * _kff;
return ... + _target * _kff;

In modern ArduPilot versions, this is often set to 0.0 by default because the kinematic shaper and high P-gains handle most use cases. However, for specialized flight profiles like high-speed object tracking, it is an essential tuning tool.

Tuning & Behavior

  • Default Value: 0.0 (Standard)
  • Range: 0.0 - 6.0
  • Effect of Increasing: Snappier starts and stops. Better "lead" in autonomous missions.
  • Effect of Decreasing: Smoother, more organic-feeling movement.

Use Case Recommendations

  • Racing / FPV Chase: Increase to 0.5 - 1.0. Allows the drone to mimic the pilot's inputs with zero perceived lag, which is critical when chasing a moving subject.
  • Standard GPS Photography: Keep at 0.0. You want the drone to be smooth and predictable; any "jumpiness" from high FF gains will ruin shots.
  • Precision Docking: Increase to 0.2. Helps the drone make tiny, instantaneous adjustments when closing the final few centimeters to a target.

Troubleshooting

  • Scenario: When you push the stick forward, the drone "nods" its nose down too far, then lifts it back up slightly as it reaches speed.
    • Diagnosis: PSC_VELXY_FF is too high (Initial overshoot).
    • Fix: Reduce PSC_VELXY_FF or set to 0.0.

PSC_VELXY_FLTD

Hz
Default 5.0
Range 0 100

Position Control Velocity (XY) D-Term Filter (PSC_VELXY_FLTD)

Description

PSC_VELXY_FLTD is the "heat shield" for your motors. In a PID loop, the Derivative (D) term is extremely sensitive to noise. Because the D-term looks at the rate of change of error, small, high-frequency vibrations in the IMU (noise) look like massive velocity changes to the math, leading to "noisy" motor outputs.

This filter specifically targets the D-term calculation, stripping away the high-frequency vibration before it gets amplified by PSC_VELXY_D.

  • Low Frequency (e.g. 2Hz): Very smooth, but makes the D-term laggy. This may lead to overshoot because the "damping" effect happens too late.
  • High Frequency (e.g. 20Hz): Instant damping, but carries a high risk of "motor chirping" or overheating as vibration noise passes through.
  • Disabled (0): The D-term will likely be unusable on any real aircraft due to vibration.

The Mathematics

The filter is a single-pole low-pass filter applied specifically to the derivative calculation:

$$ \vec{D}{filtered} = \vec{D}{prev} + \alpha \cdot \left( \frac{\vec{V}{err} - \vec{V}{err\_prev}}{dt} - \vec{D}\_{prev} \right) $$

Where the filter coefficient $\alpha$ is derived from PSC_VELXY_FLTD ($f\_c$):

$$ \alpha = \frac{dt}{dt + \frac{1}{2\pi f\_c}} $$

The Engineer's View

This parameter maps to _filt_D_hz in the _pid_vel_xy object.

It is applied in AC_PID_2D::update_all():

// AC_PID_2D.cpp
if (is_positive(dt)) {
    const Vector2f derivative{(_error - error_last) / dt};
    _derivative += (derivative - _derivative) * get_filt_D_alpha(dt);
}

The output of this filtered derivative is then multiplied by the D-gain: _derivative * _kd.

Tuning & Behavior

  • Default Value: 5.0 Hz
  • Range: 0 - 100 Hz
  • Effect of Increasing: crisper "stops" and tighter damping, at the cost of motor heat/vibration.
  • Effect of Decreasing: smoother vertical/horizontal behavior, but may introduce vertical bobbing or "bounce" when stopping.

Use Case Recommendations

  • Clean, Low-Vibration Frames: Increase to 10.0 Hz. If you have high-quality motors and excellent balancing, a higher D-filter allows for a more effective D-gain, leading to a "locked-in" feel.
  • Large, Noisy Vehicles: Keep at 5.0 Hz or decrease to 3.0 Hz. Large props generate significant low-frequency noise that can easily saturate the D-term.
  • Racing Drones: Increase to 15.0 - 20.0 Hz. Speed is everything; racer pilots accept some motor noise for the sake of instant damping.

Troubleshooting

  • Scenario: Motors are coming down hot after a flight in Loiter, but the tune feels good.
    • Diagnosis: High-frequency vibration is leaking through the D-term.
    • Fix: Decrease PSC_VELXY_FLTD to 4.0 or 3.0.

PSC_VELXY_FLTE

Hz
Default 5.0
Range 0 100

Position Control Velocity (XY) Error Filter (PSC_VELXY_FLTE)

Description

PSC_VELXY_FLTE is a "noise cleaner" for the velocity controller. It applies a low-pass filter to the velocity error (the difference between where you want to fly and where the EKF thinks you are flying).

GPS and EKF velocity estimates are never perfectly smooth; they contain high-frequency noise and "jitter." Without this filter, the PID controller would try to react to every tiny jitter, causing the motors to vibrate and the drone to feel "nervous."

  • Higher Frequency (e.g., 20Hz): The controller reacts faster to real velocity changes, but is more likely to pass noise to the motors.
  • Lower Frequency (e.g., 2Hz): The drone feels much smoother and "heavy," but there is more lag in the control response.
  • Too Low: Introduces so much "phase lag" that the drone may become unstable and start to orbit its target (toilet bowling).

The Mathematics

This parameter defines the Cutoff Frequency ($f\_c$) of a single-pole low-pass filter. The filter coefficient ($\alpha$) is calculated as:

$$ \alpha = \frac{dt}{dt + RC} \quad \text{where } RC = \frac{1}{2\pi f\_c} $$

The filtered error is then updated every time step:

$$ \vec{V}{err\_filtered} = \vec{V}{err\_prev} + \alpha \cdot (\vec{V}{err\_raw} - \vec{V}{err\_prev}) $$

Where:

  • $f\_c$ is PSC_VELXY_FLTE.
  • $\vec{V}{err\_raw}$ is the unfiltered error ($V{target} - V\_{current}$).

The Engineer's View

This parameter maps to _filt_E_hz in the _pid_vel_xy object.

It is applied in AC_PID_2D::update_all():

// AC_PID_2D.cpp
_error += ((_target - measurement) - _error) * get_filt_E_alpha(dt);

By filtering the error before the P, I, and D calculations, ArduPilot ensures that the entire PID loop operates on a consistent, smooth signal.

Tuning & Behavior

  • Default Value: 5.0 Hz
  • Range: 0 - 100 Hz
  • Effect of Increasing: Sharper control, better wind rejection, but increases motor noise and heat.
  • Effect of Decreasing: Smoother flight, quieter motors, but increases control lag and "drifting" tendency.

Use Case Recommendations

  • Standard GPS Drones: Keep Default (5.0 Hz). This is the sweet spot for typical GPS-based navigation.
  • Optical Flow / Indoor: Increase to 10.0 Hz. Optical flow often provides a cleaner, higher-rate velocity estimate than GPS, allowing for a higher filter cutoff and tighter control.
  • Large, Flexible Frames: Decrease to 3.0 Hz. If the drone's arms or frame are flexible, they can vibrate at 10-15Hz. Lowering the filter frequency prevents the position controller from exciting these mechanical resonances.

Troubleshooting

  • Scenario: Drone oscillates slowly (1-2 Hz) in Loiter, drawing circles in the air.
    • Diagnosis: PSC_VELXY_FLTE is likely too low (Phase Lag instability).
    • Fix: Increase PSC_VELXY_FLTE to 7.0 or 10.0.

PSC_VELXY_I

Default 1.0
Range 0.02 1.00

Position Control Velocity (XY) I Gain (PSC_VELXY_I)

Description

The PSC_VELXY_I parameter is the Integral term of the velocity controller. Its primary job is to "learn" and compensate for persistent external forces—most commonly Wind.

If PSC_VELXY_P is the "muscle" that reacts to immediate error, PSC_VELXY_I is the "memory" that notices if the P-term isn't doing enough. If the drone is commanding a 0 m/s velocity (hover) but the wind keeps pushing it backwards, the I-term builds up over time, leaning the drone further and further into the wind until the drift stops.

  • Too Low: The drone will drift significantly downwind before stopping. In fast forward flight, it may lag behind the desired speed.
  • Too High: The drone will "overshoot" when the wind stops or when stopping after a fast flight, taking a long time to level out (known as "I-term windup").

The Mathematics

This parameter scales the accumulated error over time.

$$ \vec{A}{target} += \int\_0^t (\vec{V}{target} - \vec{V}\_{current}) \cdot k\_I \cdot dt $$

Where:

  • $\vec{A}\_{target}$ is the requested acceleration (lean angle).
  • The integral $\int$ accumulates the velocity error every time step.
  • $k\_I$ is PSC_VELXY_I.

Anti-Windup: The code explicitly limits this accumulation via PSC_VELXY_IMAX to prevent the drone from building up a dangerous lean angle if it is physically stuck or held.

The Engineer's View

This parameter is the _ki member of the _pid_vel_xy object in AC_PosControl.

It is executed in AC_PID_2D::update_i():

// AC_PID_2D.cpp
Vector2f delta_integrator = (_error * _ki) * dt;
_integrator += delta_integrator;

Crucially, the integrator has Leakiness or Reset logic handled in AC_PosControl::soften_for_landing_xy(), which prevents the drone from tipping over if it is on the ground but thinks it is drifting.

Tuning & Behavior

  • Default Value: 1.0 (Standard Copter)
  • Range: 0.02 - 1.00
  • Effect of Increasing: stronger wind resistance, better holding of exact coordinates over long periods.
  • Effect of Decreasing: Less "slop" or overshoot when stopping, but potential for "toilet bowling" (orbiting the target) if wind is strong and P-gain is low.

Use Case Recommendations

  • Windy Environments / Maritime: Increase to 1.5 - 2.0.
    • Why: The drone needs to "lean into" the wind aggressively to hold position above a boat or shoreline.
  • Indoor / GPS-Denied: Decrease to 0.5.
    • Why: Without wind, a high I-term can accumulate noise from Optical Flow sensors, causing a slow, wobbling drift.
  • General: Keep Default (1.0).

Troubleshooting

  • Scenario: Drone flies to a waypoint, stops, but then slowly overshoots and has to back up.
    • Diagnosis: PSC_VELXY_I is too high (I-term windup). The drone built up a "lean forward" memory during the flight that it didn't dump fast enough when stopping.
    • Fix: Reduce PSC_VELXY_I or increase PSC_VELXY_D to dampen the stop.

PSC_VELXY_IMAX

cm/s/s
Default 1000
Range 0 4500

Position Control Velocity (XY) I-Term Maximum (PSC_VELXY_IMAX)

Description

PSC_VELXY_IMAX defines the maximum "tilt authority" given to the velocity integrator (PSC_VELXY_I).

The integrator's primary job is to fight constant wind. If a 20-knot wind is pushing your drone, the integrator builds up a permanent lean into the wind to hold position. This parameter prevents that lean from becoming too extreme. It ensures that even if the drone is struggling against a hurricane, the software won't command a tilt so steep that the drone loses lift and falls out of the sky.

  • Low Value: Limits the drone's ability to hold position in strong winds.
  • High Value: Allows the drone to lean very steeply to fight wind, but increases the risk of "windup" (where the drone stays tilted for several seconds after the wind stops).
  • Default (1000): Equivalent to 1000 cm/s² (about 10% of gravity), or roughly 6 degrees of "I-term lean."

The Mathematics

The velocity integrator ($\vec{I}$) is clamped by this value in the XY plane:

$$ \text{Length}(\vec{I}{new}) = \text{constrain}(\text{Length}(\vec{I}{prev} + \vec{V}\_{err} \cdot k\_I \cdot dt), 0, \text{IMAX}) $$

Where:

  • $\text{IMAX}$ is PSC_VELXY_IMAX.
  • The output is a 2D vector (North/East), so the magnitude of the vector is capped.

The Engineer's View

This parameter maps to _kimax in the _pid_vel_xy object.

It is applied in AC_PID_2D::update_i():

// AC_PID_2D.cpp
_integrator += delta_integrator;
_integrator.limit_length(_kimax);

Note that AC_PID_2D uses a circular (vector) limit, which is mathematically superior to capping North and East independently, as it prevents the drone from having more authority on the diagonals.

Tuning & Behavior

  • Default Value: 1000 (10.0 m/s² authority)
  • Range: 0 - 4500 (0 to 45 m/s² authority)
  • Effect of Increasing: Better position holding in extreme wind.
  • Effect of Decreasing: Safer flight in gusty conditions; reduces the chance of the drone "darting" after a windup.

Use Case Recommendations

  • Extreme High-Wind Ops (Offshore): Increase to 2000. This allows for about 12 degrees of permanent tilt to fight sustained ocean winds.
  • Precision Indoor Mapping: Decrease to 500. Indoors there is no wind; a lower IMAX prevents the integrator from learning "fake" offsets from sensor drift.
  • Racing / Acro: Keep Default. Standard values are usually sufficient as racers rely more on P-gain than I-term authority.

Troubleshooting

  • Scenario: Drone is holding position against wind, but when the wind stops, the drone "shoots" forward for a few meters before leveling out.
    • Diagnosis: Integrator Windup. PSC_VELXY_IMAX is too high, allowing too much "memory" to build up.
    • Fix: Reduce PSC_VELXY_IMAX to 800 or 500.

PSC_VELXY_P

Default 2.0
Range 0.1 6.0

Position Control Velocity (XY) P Gain (PSC_VELXY_P)

Description

The PSC_VELXY_P parameter controls how aggressively the drone adjusts its acceleration to match the desired velocity. It is the "muscle" of the position controller. While PSC_POSXY_P determines the speed you want to fly at to fix a position error, PSC_VELXY_P determines the force (lean angle) applied to achieve that speed.

  • Low Value: The drone feels "slushy" or "drifty." It takes a long time to reach the desired speed and may overshoot the stopping point because it doesn't brake hard enough.
  • High Value: The drone reacts instantly to velocity errors with sharp leans.
  • Too High: The drone will oscillate rapidly (jitter) as it over-corrects velocity noise, especially in wind.

The Mathematics

This parameter is the Proportional ($k\_P$) term of the velocity PID loop.

$$ \vec{A}{target} = k\_P \cdot (\vec{V}{target} - \vec{V}\_{current}) + \dots $$

Where:

  • $\vec{A}\_{target}$ is the requested acceleration (cm/s²).
  • $\vec{V}\_{target}$ is the desired velocity (cm/s).
  • $k\_P$ is PSC_VELXY_P.
  • Dimensionality: Since it converts Velocity ($L T^{-1}$) to Acceleration ($L T^{-2}$), the unit of $k\_P$ is technically $1/s$ (Hertz), though it is treated as a unitless scalar in the GCS.

The Engineer's View

This parameter is part of the AC_PID_2D object _pid_vel_xy inside AC_PosControl.

It is executed in AC_PosControl::update_xy_controller():

// AC_PosControl.cpp
Vector2f accel_target = _pid_vel_xy.update_all(_vel_target.xy(), comb_vel, _dt, _limit_vector.xy());

The output accel_target is then converted to lean angles (_roll_target, _pitch_target) which are sent to the Attitude Controller.

Tuning & Behavior

  • Default Value: 2.0 (Standard Copter)
  • Range: 0.1 - 6.0
  • Effect of Increasing: Sharper tracking of velocity requests. Better wind rejection.
  • Effect of Decreasing: Smoother flight, less "twitchiness," but reduced position holding accuracy.
  • Dependencies: Must be tuned in conjunction with PSC_VELXY_D (Damping). High P usually requires some D to prevent overshoot.

Use Case Recommendations

  • Cinematography / Heavy Lift: Decrease to 1.0 - 1.5.
    • Why: Smoothes out the "twitch" caused by GPS noise or wind gusts. Prevents the drone from jerking the camera gimbal when it corrects small position errors.
  • FPV Racing / Aggressive Flight: Increase to 2.5 - 3.0.
    • Why: Ensures the drone "locks" onto velocity commands instantly. Essential for sharp cornering where any lag results in a wide turn radius.
  • Long-Range Mapping: Keep Default (2.0).
    • Why: Standard tuning provides the best compromise between track adherence (straight lines) and efficiency.

Troubleshooting

  • Scenario: Drone "twitches" rapidly while hovering in wind.
    • Diagnosis: PSC_VELXY_P is too high. The controller is reacting to every tiny gust with a hard lean.
    • Fix: Reduce PSC_VELXY_P (try 1.5).
  • Scenario: Drone drifts away from target in wind and takes too long to correct.
    • Diagnosis: PSC_VELXY_P (or I) is too low.
    • Fix: Increase PSC_VELXY_P.

PSC_VELZ_D

Default 0.0
Range 0.0 1.0

Position Control Velocity (Vertical) D Gain (PSC_VELZ_D)

Description

PSC_VELZ_D acts as a vertical damper for the drone's climb and descent rates. It works in the middle loop of the altitude controller to smooth out the transition between climbing and hovering.

By looking at how fast the vertical velocity error is changing, the D-term can "predict" when the drone is about to reach its target speed and begin braking early. This prevents the drone from "launching" past its target altitude and then having to correct back down.

  • Note: Just like the vertical I-term, this is often set to 0.0 in standard configurations. The natural damping of the propellers and the high-frequency response of the innermost acceleration loop are usually sufficient for vertical stability.
  • Too Low: The drone may overshoot its climb rate setpoint, leading to slightly jerky vertical movement.
  • Too High: Can introduce high-frequency motor noise and vibration, as the controller over-reacts to tiny vertical speed fluctuations (e.g., from Baro noise).

The Mathematics

This parameter scales the derivative of the vertical velocity error:

$$ \vec{A}{z\_target} += k\_D \cdot \text{Filter}\left( \frac{d(V{z\_target} - V\_{z\_current})}{dt} \right) $$

Where:

  • $k\_D$ is PSC_VELZ_D.
  • $ ext{Filter}(\dots)$ is a low-pass filter (set by PSC_VELZ_FLTD) to clean up the derivative signal.

The Engineer's View

This parameter is the _kd member of the _pid_vel_z object inside AC_PosControl.

It is executed in AC_PID_Basic::update_all():

// AC_PID_Basic.cpp
if (is_positive(dt)) {
    float derivative = (error - _last_error) / dt;
    _derivative = _last_derivative + (dt / (_filt_D_hz + dt)) * (derivative - _last_derivative);
}
return ... + _derivative * _kd;

Vertical damping is typically handled by the innermost PSC_ACCZ_D gain first, with PSC_VELZ_D acting as a secondary, slower damping layer.

Tuning & Behavior

  • Default Value: 0.0 (Standard)
  • Range: 0.0 - 1.0
  • Effect of Increasing: Smoother vertical starts and stops. Less "vertical bobbing" during aggressive climbs.
  • Effect of Decreasing: Maximum vertical responsiveness, but potential for "bounce" when stopping a climb.

Use Case Recommendations

  • Standard Build: Keep at 0.0. Vertical aerodynamics usually provide enough damping.
  • Large, Low-RPM Propellers: Consider 0.05 - 0.1. Large props have high vertical "surge" and slow response; a small amount of velocity damping can help level them out.
  • Precision Lifting / Construction: Increase to 0.1. Helps the drone move vertically in a very deliberate, smooth manner.

Troubleshooting

  • Scenario: Drone oscillates vertically at a moderate speed (once every 0.5 seconds) specifically when you let go of the throttle stick.
    • Diagnosis: Inadequate vertical damping.
    • Fix: Increment PSC_VELZ_D by 0.02 and see if the settle time improves.

PSC_VELZ_FF

Default 0.0
Range 0 1.0

Position Control Velocity (Vertical) Feed-Forward (PSC_VELZ_FF)

Description

PSC_VELZ_FF provides "pre-emptive" vertical force. While the P and I terms in the vertical velocity loop wait for the drone to miss its target speed before they act, the Feed-Forward (FF) term acts the moment you move the throttle stick.

If you command a 1 m/s climb, the FF term instantly calculates a requested acceleration to start the drone moving upward. This significantly reduces the vertical "sag" or "delay" felt in altitude-controlled modes (AltHold, Loiter).

  • Standard Build: Often set to 0.0 because the shaper and high vertical P-gain handle most situations.
  • Performance Build: A small amount of FF makes altitude changes feel "punchier" and more professional.

The Mathematics

The FF term is proportional to the vertical speed target:

$$ \vec{A}{z\_target\_FF} = \vec{V}{z\_target} \cdot k\_{FF} $$

Where:

  • $\vec{V}\_{z\_target}$ is the commanded climb/descent rate.
  • $k\_{FF}$ is PSC_VELZ_FF.

The Engineer's View

This parameter maps to _kff in the _pid_vel_z object.

It is applied in AC_PosControl::update_z_controller():

// AC_PosControl.cpp
_vel_target.z += _vel_desired.z + _vel_offset.z + _vel_terrain;
// ...
_accel_target.z = _pid_vel_z.update_all(_vel_target.z, curr_vel_z, ...);

The AC_PID_Basic library includes the FF term in its final output calculation. It effectively "leads" the acceleration target, reducing the work the P-term has to do.

Tuning & Behavior

  • Default Value: 0.0 (Standard)
  • Range: 0.0 - 1.0
  • Effect of Increasing: Snappier response to throttle stick changes. Less vertical altitude loss at the start of a climb.
  • Effect of Decreasing: Smoother, more damped vertical movement.

Use Case Recommendations

  • Heavy Cargo VTOL: Set to 0.1. Helps the drone overcome the huge vertical inertia of a heavy frame to start moving the moment the command is given.
  • FPV Freestyle in Loiter: Set to 0.2. Makes vertical "pops" feel more like a manual Acro quad.
  • Standard GPS Photography: Keep at 0.0. Smoothness is priority; raw stick-to-acceleration mapping can sometimes be too "jumpy."

Troubleshooting

  • Scenario: When you push the throttle stick up, the drone "jumps" up suddenly and then settles into the climb rate.
    • Diagnosis: PSC_VELZ_FF is too high (initial jerk overshoot).
    • Fix: Reduce PSC_VELZ_FF or set to 0.0.

PSC_VELZ_FLTD

Hz
Default 5.0
Range 0 100

Position Control Velocity (Vertical) D-Term Filter (PSC_VELZ_FLTD)

Description

PSC_VELZ_FLTD is the specific filter for the vertical Derivative (D) gain in the velocity loop.

Because the D-term (PSC_VELZ_D) reacts to the acceleration of vertical errors, it is extremely sensitive to sensor noise and air turbulence. Without this filter, the D-term would amplify tiny "jitters" in the barometer signal into large, rapid throttle changes. This filter strips away those high-frequency jitters, ensuring that the damping effect only applies to the real vertical movements of the drone.

  • Note: If PSC_VELZ_D is 0 (the default), this parameter does nothing.
  • Safety: If you do enable vertical velocity damping, you must have this filter set to a reasonable value (5-10Hz) to protect your ESCs from noise spikes.

The Mathematics

The filter is a single-pole low-pass filter applied specifically to the vertical velocity derivative calculation:

$$ \vec{D}{z\_filtered} = \vec{D}{z\_prev} + \alpha \cdot \left( \frac{d(V\_{z\_err})}{dt} - \vec{D}\_{z\_prev} \right) $$

Where the filter coefficient $\alpha$ is derived from PSC_VELZ_FLTD ($f\_c$):

$$ \alpha = \frac{dt}{dt + \frac{1}{2\pi f\_c}} $$

The Engineer's View

This parameter maps to _filt_D_hz in the _pid_vel_z object.

It is applied in AC_PID_Basic::update_all():

// AC_PID_Basic.cpp
if (is_positive(dt)) {
    float derivative = (error - _last_error) / dt;
    _derivative = _last_derivative + (dt / (_filt_D_hz + dt)) * (derivative - _last_derivative);
}

This filter provides a "cushion" for the vertical damping logic, preventing the drone from having an aggressive vertical "bark" when it encounters turbulence.

Tuning & Behavior

  • Default Value: 5.0 Hz
  • Range: 0 - 100 Hz
  • Effect of Increasing: Allows for higher vertical D-gains with less lag, but risk of motor heat.
  • Effect of Decreasing: Smoother vertical damping, but the D-term may become too laggy to stop altitude bobbing.

Use Case Recommendations

  • Standard Build: Keep at 5.0 Hz. (If PSC_VELZ_D is used).
  • Large, Low-Frequency Propellers: Decrease to 3.0 Hz. Large props create low-frequency "chuffing" that can easily trigger a noisy D-term.
  • High-End Autonomy: Increase to 10.0 Hz. Provides the fast vertical damping needed for precision tasks like lidar-based power line inspection.

Troubleshooting

  • Scenario: Motors are getting warm and making a rhythmic "pulsing" sound during vertical descents.
    • Diagnosis: D-term noise from the vertical velocity loop.
    • Fix: Decrease PSC_VELZ_FLTD to 4.0 or 3.0 Hz, or reduce PSC_VELZ_D.

PSC_VELZ_FLTE

Hz
Default 5.0
Range 0 100

Position Control Velocity (Vertical) Error Filter (PSC_VELZ_FLTE)

Description

PSC_VELZ_FLTE smooths the drone's vertical performance by cleaning up noise in the climb/descent speed measurement.

Vertical velocity is primarily estimated using a combination of the Barometer and Accelerometers. Barometers are notoriously noisy—they are affected by wind gusts blowing into the drone's frame and even by the drone's own propeller wash. Without this filter, the vertical PID controller would try to react to every tiny "pop" in the pressure sensor, causing the motors to stutter and the drone to sound uneven.

  • Higher Frequency (e.g. 10Hz): Faster response to real climb rate changes, but more likely to make the motors sound "jittery."
  • Lower Frequency (e.g. 2Hz): Extremely smooth vertical flight, but makes the drone slow to react to changes in terrain.
  • Default (5Hz): Optimal for most Baro-based altitude hold systems.

The Mathematics

This parameter defines the Cutoff Frequency ($f\_c$) for a low-pass filter:

$$ \vec{V}{z\_err\_filtered} = \vec{V}{z\_err\_prev} + \alpha \cdot (\vec{V}{z\_err\_raw} - \vec{V}{z\_err\_prev}) $$

Where the smoothing factor $\alpha$ is:
$$ \alpha = \frac{dt}{dt + \frac{1}{2\pi f\_c}} $$

A lower PSC_VELZ_FLTE value creates a smaller $\alpha$, meaning the drone trusts its previous state more than the new (potentially noisy) measurement.

The Engineer's View

This parameter maps to _filt_E_hz in the _pid_vel_z object.

It is applied in AC_PID_Basic::update_all():

// AC_PID_Basic.cpp
_error += ((target - measurement) - _error) * get_filt_E_alpha(dt);

By filtering the vertical error here, ArduPilot ensures that the "Velocity P-Gain" (PSC_VELZ_P) acts on a smooth signal, preventing high-frequency throttle oscillations while maintaining a precise hover.

Tuning & Behavior

  • Default Value: 5.0 Hz
  • Range: 0.0 - 100.0 Hz
  • Effect of Increasing: Snappier throttle response, drone stops its vertical movement more accurately at the cost of motor noise.
  • Effect of Decreasing: Quieter, smoother flight; great for cinematography.

Use Case Recommendations

  • Standard Build: Keep at 5.0 Hz. This provides excellent results for most users.
  • Rangefinder-Only Flight (Indoor): Increase to 10.0 Hz. Rangefinders are much cleaner than barometers; you can afford a higher filter frequency to get tighter vertical control.
  • Large-Scale Survey Drones: Keep Default. Smoothness is more important than millisecond-level vertical accuracy for mapping.

Troubleshooting

  • Scenario: Drone hovers at the right height, but the motors sound like they are "pulsing" or "surging" rapidly.
    • Diagnosis: Baro noise is passing through the filter.
    • Fix: Decrease PSC_VELZ_FLTE to 3.0 Hz.

PSC_VELZ_I

Default 0.0
Range 0.02 1.00

Position Control Velocity (Vertical) I Gain (PSC_VELZ_I)

Description

PSC_VELZ_I is the Integral term for the vertical velocity controller. It works to eliminate persistent errors in climb or descent rates.

While the innermost acceleration loop (PSC_ACCZ_I) handles gravity and hover throttle, the vertical velocity loop ensures that if you command a 1 m/s climb, you actually get exactly 1 m/s, even if there is an updraft or downdraft.

  • Note: In many multirotor configurations, this is set to 0.0 by default. This is because the innermost Acceleration loop is so effective at maintaining the vertical state that an additional integrator in the velocity loop often adds unnecessary complexity and potential for oscillation.
  • Too Low: The drone may not reach its target climb/descent speed in high-drag situations.
  • Too High: Can cause vertical "surging" or low-frequency bouncing during altitude changes.

The Mathematics

This parameter scales the accumulation of vertical velocity error:

$$ \vec{A}{z\_target} += \int\_0^t (V{z\_target} - V\_{z\_current}) \cdot k\_I \cdot dt $$

Where:

  • $k\_I$ is PSC_VELZ_I.
  • The integral accumulates the error between commanded and actual vertical speed.

The Engineer's View

This parameter is the _ki member of the _pid_vel_z object (class AC_PID_Basic) inside AC_PosControl.

It is executed in AC_PosControl::update_z_controller():

// AC_PosControl.cpp
_accel_target.z = _pid_vel_z.update_all(_vel_target.z, curr_vel_z, _dt, ...);

By default, the AC_PID_Basic vertical velocity PID is initialised with kI = 0 in the AC_PosControl constructor.

Tuning & Behavior

  • Default Value: 0.0 (Standard Multirotor)
  • Range: 0.02 - 1.00
  • Effect of Increasing: Better adherence to target climb rates under load or in heavy vertical wind.
  • Effect of Decreasing: Smoother vertical transitions, less vertical "hunting."

Use Case Recommendations

  • Heavy Lift / Tethered: Consider setting to 0.1. Helps the drone overcome the constant downward pull of a heavy cable to maintain a precise climb rate.
  • Standard GPS Drones: Keep at 0.0. The default cascaded architecture is designed to work without this integrator.
  • High Performance / Racing: Keep at 0.0. Vertical speed is handled by the high-frequency P-gain (PSC_VELZ_P) and the Acceleration loop.

Troubleshooting

  • Scenario: Drone oscillates up and down slowly (1 second per bounce) only when climbing at high speeds.
    • Diagnosis: PSC_VELZ_I is too high, causing vertical phase lag.
    • Fix: Reduce PSC_VELZ_I to 0.0 or 0.05.

PSC_VELZ_IMAX

Default 1000
Range 1.0 8.0

Position Control Velocity (Vertical) I-Term Maximum (PSC_VELZ_IMAX)

Description

PSC_VELZ_IMAX is a safety clamp for the vertical velocity loop. It limits the maximum "correction authority" that the integrator (PSC_VELZ_I) can accumulate over time.

While the innermost loop has its own limit (PSC_ACCZ_IMAX) for hover throttle, this middle loop limit ensures that the software doesn't "try too hard" to maintain a specific climb rate if the vehicle is physically unable to do so (e.g., if it is carrying an overweight payload or is stuck). It prevents the drone from building up a massive "power surge" that would cause it to rocket upwards if the physical resistance suddenly disappeared.

  • Standard Build: Often set to 1000 (full authority), but since the vertical velocity integrator is usually disabled (I=0), this parameter often has no practical effect.
  • Safety: Always keep this at a reasonable value to prevent runaway vertical commands.

The Mathematics

The vertical velocity integrator is constrained to this maximum value:

$$ \vec{I}{new} = \text{constrain}(\vec{I}{prev} + \text{error} \cdot k\_I \cdot dt, -\text{IMAX}, \text{IMAX}) $$

Where:

  • $\text{IMAX}$ is PSC_VELZ_IMAX.
  • The output is typically scaled to match the units of vertical acceleration.

The Engineer's View

This parameter maps to _kimax in the _pid_vel_z object.

It is applied in AC_PID_Basic::update_all():

// AC_PID_Basic.cpp
_integrator = constrain_float(_integrator + (error * _ki * dt), -_kimax, _kimax);

Just like the other PID loops in ArduPilot, this integrator is also protected by "Saturation Checking"—it will stop increasing if the output throttle has already reached 100%, regardless of the IMAX setting.

Tuning & Behavior

  • Default Value: 1000 (Standard)
  • Range: 1.0 - 8.0 (Internal units vary)
  • Effect of Increasing: Allows the drone to maintain more consistent climb rates under extreme loads.
  • Effect of Decreasing: Safer; limits the maximum "punch" the velocity controller can add over long periods.

Use Case Recommendations

  • Tethered Operations: Decrease to 300. Limits the tension the drone can put on the cable if the vertical path planner fails.
  • Standard Flight: Keep at Default (1000). This is a safe ceiling for normal operation.

Troubleshooting

  • Scenario: Drone holds climb rate perfectly for the first 10 seconds of a heavy lift, then starts to slowly lose speed.
    • Diagnosis: PSC_VELZ_IMAX is likely being hit. The drone needs more integrator authority to maintain the speed against the weight.
    • Fix: Increase PSC_VELZ_IMAX or increase PSC_VELZ_P to reduce reliance on the integrator.

PSC_VELZ_P

Default 5.0
Range 1.0 8.0

Position Control Velocity (Vertical) P Gain (PSC_VELZ_P)

Description

PSC_VELZ_P is the "throttle response" of the altitude controller. While PSC_POSZ_P determines what climb rate we want, PSC_VELZ_P determines how much force (vertical acceleration) the drone applies to achieve that rate.

  • Low Value: The drone feels "underpowered" vertically. It takes a long time to reach its target climb rate. If you increase the throttle stick, the drone will accelerate slowly.
  • High Value: The drone reacts instantly to vertical commands.
  • Too High: The drone will oscillate vertically at a high frequency, sounding like a "vibration" in the motors, especially during rapid descents.

The Mathematics

This parameter is the Proportional ($k\_P$) term in the inner Vertical Velocity loop.

$$ A\_{z\_target} = k\_P \cdot (V\_{z\_target} - V\_{z\_current}) + \dots $$

Where:

  • $A\_{z\_target}$ is the requested vertical acceleration (cm/s²) sent to the Accel controller.
  • $V\_{z\_target}$ is the desired climb/descent rate.
  • $V\_{z\_current}$ is the current EKF vertical velocity.
  • $k\_P$ is PSC_VELZ_P.
  • Dimensionality: Since it converts Velocity ($L T^{-1}$) to Acceleration ($L T^{-2}$), the unit of $k\_P$ is $1/s$ (Hertz).

The Engineer's View

This parameter is the _kp member of the _pid_vel_z object (class AC_PID_Basic) inside AC_PosControl.

It is executed in AC_PosControl::update_z_controller():

// AC_PosControl.cpp
_accel_target.z = _pid_vel_z.update_all(_vel_target.z, curr_vel_z, _dt, _motors.limit.throttle_lower, _motors.limit.throttle_upper);

The output _accel_target.z is then combined with the feed-forward and gravity compensation to determine the final throttle output.

Tuning & Behavior

  • Default Value: 5.0
  • Range: 1.0 - 8.0
  • Effect of Increasing: Faster vertical acceleration. Drone maintains climb rate more accurately under varying loads.
  • Effect of Decreasing: Smoother, softer vertical movement.

Use Case Recommendations

  • Standard Multirotors: Keep Default (5.0). ArduPilot defaults are very well tuned for vertical response on 4-10 inch props.
  • Large / Heavy Vehicles: Decrease to 3.0 - 4.0. Heavy vehicles cannot accelerate vertically as fast as small ones; a high P-gain will lead to "ringing" in the throttle.
  • Precision Docking / Precision Landing: Increase to 6.0. Ensures the vertical velocity is perfectly matched to the descent profile to avoid hard landings.

Troubleshooting

  • Scenario: Drone "jitters" or makes a high-pitched oscillation sound only when climbing or descending.
    • Diagnosis: PSC_VELZ_P is too high for the motor/prop combination.
    • Fix: Reduce PSC_VELZ_P by 0.5 until the noise stops.