MAVLINKHUD

Overview

The H parameter group (often appearing as H_ or HELI_) is the comprehensive configuration set for Traditional Helicopters (Single Main Rotor + Tail Rotor, or Tandem).

ArduPilot's helicopter support is world-class, handling complex swashplate mixing, governor control, and autorotation.

Key Concepts

1. Swashplate Mixing (H_SW_...)

Defines the mechanical arrangement of the servos driving the main rotor.

  • H_SW_TYPE: Supports H3, H1, H4, and others.
  • H_SW_COL_DIR: Reverses the collective pitch direction.

2. Rotor Speed Control (RSC)

Manages the motor/engine power to maintain a constant rotor RPM.

  • H_RSC_MODE: 1 (Interlocked PWM), 2 (Set-point), 3 (Throttle Curve), or 4 (Governor).
  • H_RSC_SETPOINT: The target rotor speed.

3. Tail Rotor Configuration (H_TAIL_...)

  • H_TAIL_TYPE: 0 (Servo), 1 (Servo with yaw-to-collective mix), 2 (Direct Drive Fixed Pitch - DDFP).
  • H_COL2YAW: Collective-to-Yaw compensation (pre-compensates for torque changes).

4. Collective Limits (H_COL_...)

  • H_COL_MIN / MAX: The allowable range of collective pitch (e.g., -3 degrees to +12 degrees).

Parameter Breakdown

  • H_RSC_MODE: The "throttle" logic for the main rotor.
  • H_COL_HOVER: The collective pitch required for a stable hover (learned or manual).
  • H_FLYBAR_MODE: Enables logic for legacy mechanical flybar heads (0 for Flybarless).

Integration Guide

  • Safety: Always use a Motor Interlock switch. Helicopters are physically dangerous; the Interlock ensures the rotor only spins when commanded.
  • Servo Check: Use the H_SV_TEST feature to verify swashplate movement before mounting blades.

Developer Notes

  • Library: libraries/AP_Motors/AP_MotorsHeli_Single.cpp, AP_MotorsHeli_Tandem.cpp.
  • Complexity: Helicopter tuning is significantly more complex than Multicopter tuning and relies heavily on accurate collective/yaw pre-compensation.

H_COL2YAW

Default 0
Range -2 2

Collective-Yaw Mixing (H_COL2YAW)

Description

Compensates for the changing torque of the main rotor as collective pitch increases. By automatically adding a pre-calculated amount of tail rotor thrust, this reduces the work required by the yaw PID controller and results in a more stable heading during aggressive climbs.

H_COL2_MAX

deg
Default 45
Range 20 80

Tiltrotor maximum VTOL angle

Note: This parameter functions identically to H_COL_MAX.

H_COL2_MIN

PWM
Default AP_MOTORS_HELI_DUAL_COLLECTIVE2_MIN
Range 1000 2000

Swash 2 Minimum Collective Pitch

Note: This parameter functions identically to H_COL_MIN.

H_COL_ANG_MAX

deg
Default 10
Range 5 20

Collective Blade Pitch Angle Maximum (H_COL_ANG_MAX)

Description

The physical blade pitch angle (in degrees) when the swashplate is at its maximum position. This must be measured during setup.

H_COL_ANG_MIN

deg
Default -10
Range -20 0

Collective Blade Pitch Angle Minimum (H_COL_ANG_MIN)

Description

The physical blade pitch angle (in degrees) when the swashplate is at its minimum position. This must be measured during setup.

H_COL_HOVER

Default 0.5
Range 0.3 0.8

Collective Hover Value (H_COL_HOVER)

Description

The specific collective pitch setting required to maintain a stationary hover. This serves as the center-point for altitude control logic.

H_COL_LAND_MIN

deg
Default -2
Range -5 0

Collective Pitch Minimum when Landed (H_COL_LAND_MIN)

Description

Restricts the minimum collective pitch while the aircraft is detected as "Landed" in automated modes (like AltHold). This prevents the aircraft from being forced onto the ground with excessive negative pitch.

H_COL_MAX

PWM
Default 1750
Range 1000 2000

Maximum Collective Pitch (H_COL_MAX)

Description

Defines the maximum physical travel limit of the swashplate for collective pitch control.

H_COL_MIN

PWM
Default 1250
Range 1000 2000

Minimum Collective Pitch (H_COL_MIN)

Description

Defines the minimum physical travel limit of the swashplate for collective pitch control.

H_COL_ZERO_THRST

deg
Default 0.0
Range -5 0

Collective Blade Pitch at Zero Thrust (H_COL_ZERO_THRST)

Description

The blade pitch angle (typically 0 degrees for symmetrical blades) at which the main rotor produces zero lift.

H_CYC_MAX

Default 4500
Range 0 4500

Maximum Cyclic Pitch Angle (H_CYC_MAX)

Description

Defines the maximum angular authority of the swashplate for roll and pitch maneuvers.

  • Typically adjusted to achieve 6-7 degrees of physical blade pitch change.

H_DCP_SCALER

Default 0.25
Range 0 1.0

Dual Cyclic Pitch Scaler (H_DCP_SCALER)

Description

H_DCP_SCALER is used for Tandem (two-rotor) helicopters like the CH-47 Chinook.

In a tandem helicopter, yaw is controlled by tilting the two swashplates in opposite directions (Differential Cyclic Pitch). This parameter scales that effect.

  • Tuning: Adjust so that the yaw response is balanced and does not cause unwanted rolling or pitching.

H_DCP_TRIM

Default 0
Range -0.1 0.1

Direct Cyclic Pitch Trim (H_DCP_TRIM)

Description

H_DCP_TRIM provides a static offset to the cyclic pitch.

H_DCP_YAW

Default 0
Range -1 1

Direct Cyclic Pitch Yaw (H_DCP_YAW)

Description

H_DCP_YAW adds a tail kick when you move the cyclic stick.

This is a feed-forward term. If you slam the stick forward, the main rotor torque changes. This parameter tells the tail to compensate instantly, rather than waiting for the gyro to detect a yaw error.

H_DDFP_BAT_IDX

Default 0
Range 0 10

DDVP Battery Index (H_DDFP_BAT_IDX)

Description

H_DDFP_BAT_IDX tells the tail mixer which battery to watch.

If you have a separate battery for the tail motor (uncommon) or if your main battery is on Monitor 2, set this index accordingly.

  • 0: Battery Monitor 1.
  • 1: Battery Monitor 2.

H_DDFP_BAT_V_MAX

V
Default 0
Range 0 100

DDVP Battery Voltage Max (H_DDFP_BAT_V_MAX)

Description

H_DDFP_BAT_V_MAX sets the "Full Charge" reference.

When the battery is at this voltage, the mixer applies 100% of the requested throttle.

Tuning & Behavior

  • Default Value: 0 (Disabled).
  • Recommendation: Set to 4.2V * Cell Count (e.g. 25.2V for 6S).

H_DDFP_BAT_V_MIN

V
Default 0
Range 0 100

DDVP Battery Voltage Min (H_DDFP_BAT_V_MIN)

Description

H_DDFP_BAT_V_MIN sets the "Empty" reference.

As the battery drops to this level, the mixer boosts the PWM signal to the ESC to compensate for the lower voltage, keeping the RPM consistent.

Tuning & Behavior

  • Default Value: 0.
  • Recommendation: Set to 3.3V * Cell Count.

H_DDFP_SPIN_MAX

Default 0.95
Range 0.8 1.0

DDFP Tail Motor Spin Maximum (H_DDFP_SPIN_MAX)

Description

H_DDFP_SPIN_MAX defines the saturation point for the tail motor.

H_DDFP_SPIN_MIN

Default 0.15
Range 0 0.3

DDFP Tail Motor Spin Minimum (H_DDFP_SPIN_MIN)

Description

H_DDFP_SPIN_MIN sets the lower limit for a fixed-pitch tail motor.

If you are using a standard drone motor for your tail, this is the point where it produces reliable thrust. Setting this correctly ensures the tail doesn't "Stall" or stop spinning during low-torque maneuvers.

H_DDFP_THST_EXPO

Default 0
Range 0 1

DDVP Tail Thrust Expo (H_DDFP_THST_EXPO)

Description

H_DDFP_THST_EXPO linearizes the thrust of the tail motor.

Propeller thrust is roughly proportional to RPM^2. This parameter applies the inverse curve so that a 50% yaw command results in 50% thrust, not 25%.

Tuning & Behavior

  • 0.65: Typical for 5-inch props.
  • 0: Linear output (bad for thrust).

H_DUAL_MODE

Default 0
Range 0 2

Dual Heli Rotor Mode (H_DUAL_MODE)

Description

H_DUAL_MODE tells ArduPilot what kind of multi-rotor helicopter you are flying.

Standard helicopters have one main rotor and one tail rotor. "Dual" helicopters use two large rotors to generate lift.

  • 0: Tandem. Rotors are arranged front-to-back (like a Chinook CH-47).
  • 1: Coaxial. Two rotors stacked on top of each other on a single shaft.
  • 2: Intermeshing. Rotors are side-by-side and tilt slightly towards each other (like a K-MAX).

Tuning & Behavior

  • Default Value: 0.
  • Reboot Required: Yes.

H_FLYBAR_MODE

Default 0
Range 0 1

Flybar Mode Selector (H_FLYBAR_MODE)

Description

Tells the attitude controller if the aircraft has a physical flybar.

  • 0: NoFlybar (Modern digital FBL system)
  • 1: Flybar (Legacy mechanical stabilization)

H_GYR_GAIN

PWM
Default 0
Range 0 1000

External Gyro Gain (H_GYR_GAIN)

Description

Specifies the gain value sent to an external tail-lock gyroscope.

  • Only used if H_TAIL_TYPE is set to 1 (Servo with External Gyro).

H_GYR_GAIN_ACRO

PWM
Default 0
Range 0 1000

ACRO External Gyro Gain (H_GYR_GAIN_ACRO)

Description

H_GYR_GAIN_ACRO allows you to have a separate tail gyro sensitivity for aerobatic flying.

In ACRO mode, pilots often want a more aggressive or direct response from the tail compared to stabilized modes. This parameter overrides the standard H_GYR_GAIN when you switch to ACRO.

  • 0 (Default): Use the standard H_GYR_GAIN for all modes.
  • > 0: Use this specific value when in ACRO mode.

Tuning & Behavior

  • Recommendation: Only used if H_TAIL_TYPE = 1 (External Gyro).

H_HOVER_LEARN

Default 2
Range 0 2

Hover Value Learning (H_HOVER_LEARN)

Description

Controls whether the flight controller automatically updates the H_COL_HOVER parameter based on actual flight data.

  • 0: Disabled
  • 1: Learn (Volatile)
  • 2: Learn and Save (Permanent)

H_OFFSET

Default 0
Range -0.1 0.1

Heli Cyclic Offset (H_OFFSET)

Description

H_OFFSET provides a global trim for the swashplate.

H_OPTIONS

Default 1

Heli_Options (H_OPTIONS)

Description

Configuration bitmask for helicopter flight behaviors.

  • Bit 0: Use Leaky I (Recommended for most setups to prevent integrator windup on the ground).

H_RSC_AROT_ENBL

Default 0
Range 0 1

Enable Autorotation Handling (H_RSC_AROT_ENBL)

Description

H_RSC_AROT_ENBL activates specialized logic for "Dead-Stick" landings on helicopters.

Autorotation is a maneuver where the main rotor is driven by the upward flow of air during a descent, allowing the helicopter to land safely even if the motor fails. This parameter enables the autopilot to recognize an autorotation state and correctly manage the transition back to powered flight (Bailout) if the engine is restarted in mid-air.

Tuning & Behavior

  • Default Value: 0 (Disabled).
  • Recommendation: Enable this if you practice autorotations or have a high-value helicopter where a mid-air motor restart is possible.

H_RSC_AROT_IDLE

%
Default 0
Range 0 40

Autorotation Idle Throttle (H_RSC_AROT_IDLE)

Description

H_RSC_AROT_IDLE keeps the motor "Spinning but not Engaging" during an autorotation.

This is primarily for combustion engines or electric ESCs with a "bailout window." It ensures the engine doesn't drop to a true idle or stop completely, allowing for a much faster re-engagement of power if needed.

H_RSC_AROT_RAMP

s
Default 2.0
Range 0.1 10.0

Autorotation Bailout Ramp Time (H_RSC_AROT_RAMP)

Description

H_RSC_AROT_RAMP controls the "Power-Up Speed" after an autorotation.

If you abort an autorotation (Bailout), you want power back quickly, but not so fast that it snaps the main gears or causes a tail kick.

  • ESC with Bailout Mode: Set this to 0.1s. The ESC will handle its own fast-ramp.
  • Standard ESC: Set to 2.0s - 4.0s.

H_RSC_AROT_RUNUP

s
Default 3.0
Range 1.0 10.0

Autorotation Bailout Runup Time (H_RSC_AROT_RUNUP)

Description

H_RSC_AROT_RUNUP is a safety timer for autonomous flight.

It tells the autopilot how long it must wait for the head speed to recover before it is allowed to increase the collective pitch. If the autopilot tries to climb before the rotor is back up to speed, the extra drag will "Bog" the motor and likely cause a crash.

Tuning & Behavior

  • Default Value: 3.0 seconds.
  • Constraint: Must be at least 1 second longer than H_RSC_AROT_RAMP.

H_RSC_CLDWN_TIME

s
Default 0
Range 0 120

Cooldown Time (H_RSC_CLDWN_TIME)

Description

Automates the engine cooldown procedure for combustion or turbine engines. After landing and disarming, the engine will run at an elevated idle for this many seconds before shutting down.

  • 0 disables the cooldown feature.

H_RSC_CRITICAL

%
Default 50
Range 0 100

Critical Rotor Speed (H_RSC_CRITICAL)

Description

A safety threshold representing the minimum RPM required to maintain flight. If the (estimated or measured) rotor speed falls below this value, the autopilot will declare a loss of power.

  • Commonly set so that the threshold is crossed approximately 3 seconds after a power loss.

H_RSC_GOV_COMP

%
Default 25
Range 0 70

Governor Torque Compensator (H_RSC_GOV_COMP)

Description

Adjusts the sensitivity of the governor's altitude compensation.

H_RSC_GOV_DROOP

%
Default 25
Range 0 100

Governor Droop Compensator (H_RSC_GOV_DROOP)

Description

Controls how aggressively the governor increases throttle when a drop in rotor RPM is detected due to increased load (e.g., during a climb).

H_RSC_GOV_FF

%
Default 50
Range 0 100

Governor Feedforward (H_RSC_GOV_FF)

Description

Provides an immediate throttle increase when collective pitch is increased, anticipating the load before the RPM actually drops.

H_RSC_GOV_RANGE

RPM
Default 100
Range 50 200

Governor Operational Range (H_RSC_GOV_RANGE)

Description

Defines the safety window for the internal governor. If the measured RPM deviates from the target by more than this amount, the governor will automatically disengage and fall back to the throttle curve.

H_RSC_GOV_RPM

RPM
Default 1500
Range 800 3500

Rotor RPM Setting (H_RSC_GOV_RPM)

Description

The target operating speed for the rotors when using the AutoThrottle mode. The flight controller will attempt to maintain this exact RPM using closed-loop control.

  • Requires a functional RPM sensor.

H_RSC_GOV_TORQUE

%
Default 30
Range 10 60

Governor Torque Limiter (H_RSC_GOV_TORQUE)

Description

Limits how quickly the engine can increase torque during the initial transition to governor control, ensuring a smooth engagement of the AutoThrottle.

H_RSC_IDLE

%
Default 0
Range 0 50

Throttle Output at Idle (H_RSC_IDLE)

Description

Defines the engine idle throttle for combustion-powered helicopters. For electric helicopters, this is typically set to 0.

H_RSC_MODE

Default 1
Range 1 4

Rotor Speed Control Mode (H_RSC_MODE)

Description

Configures how the flight controller determines the throttle output for the main rotor.

  • 1: RC Passthrough (Direct control from transmitter)
  • 2: External Gov SetPoint (Uses H_RSC_SETPOINT)
  • 3: Throttle Curve (Uses 5-point curve based on collective)
  • 4: AutoThrottle (Advanced internal governor requiring RPM sensor)

H_RSC_RAMP_TIME

s
Default 1
Range 0 60

Throttle Ramp Time (H_RSC_RAMP_TIME)

Description

Controls how quickly the throttle signal increases when starting the motor. A slower ramp prevents sudden torque spikes that could damage the gears or drive belts.

H_RSC_RUNUP_TIME

s
Default 10
Range 0 60

Rotor Runup Time (H_RSC_RUNUP_TIME)

Description

Specifies the physical time required for the rotors to reach full speed. This is used by the flight controller to ensure that it doesn't attempt to take off or enter stabilized modes before the rotors have sufficient inertia.

  • Must be set longer than H_RSC_RAMP_TIME.

H_RSC_SETPOINT

%
Default 70
Range 0 100

External Motor Governor Setpoint (H_RSC_SETPOINT)

Description

Defines the target throttle percentage sent to an external Electronic Speed Controller (ESC) or governor. This value is used when the pilot enables the "Motor Interlock" (throttle hold off).

  • Typical values range from 60% to 80% depending on the desired head speed.

H_RSC_SLEWRATE

%/s
Default 0
Range 0 500

Throttle Slew Rate (H_RSC_SLEWRATE)

Description

Limits the maximum speed of throttle signal changes. This prevents sudden engine surging or mechanical strain.

  • 0: Unlimited
  • 100: Full range in 1 second

H_RSC_THRCRV_0

%
Default 25
Range 0 100

Throttle Curve at 0% Coll (H_RSC_THRCRV_0)

Description

Part of a 5-point throttle curve (0, 25, 50, 75, 100). Defines the motor power required when collective pitch is at its minimum.

H_RSC_THRCRV_100

%
Default 100
Range 0 100

Throttle Curve at 100% Coll (H_RSC_THRCRV_100)

Description

Final point of the 5-point throttle curve.

H_RSC_THRCRV_25

%
Default 32
Range 0 100

Throttle Curve at 25% Coll (H_RSC_THRCRV_25)

Description

Second point of the 5-point throttle curve.

H_RSC_THRCRV_50

%
Default 38
Range 0 100

Throttle Curve at 50% Coll (H_RSC_THRCRV_50)

Description

Middle point of the 5-point throttle curve.

H_RSC_THRCRV_75

%
Default 50
Range 0 100

Throttle Curve at 75% Coll (H_RSC_THRCRV_75)

Description

Fourth point of the 5-point throttle curve.

H_SV_MAN

Default 0
Range 0 4

Manual Servo Mode (H_SV_MAN)

Description

A setup tool that forces the swashplate servos into specific positions (Max, Min, or Passthrough) to assist in mechanical leveling and linkage adjustment.

  • WARNING: Must be set to 0 (Disabled) before attempting flight.

H_SV_TEST

Default 0
Range 0 10

Boot-up Servo Test Cycles (H_SV_TEST)

Description

Commands the swashplate servos to perform a pre-defined movement sequence upon power-up, allowing the pilot to visually confirm that all linkages are functioning correctly.

H_SW2_COL_DIR

null
Default COLLECTIVE_DIRECTION_NORMAL
Range null

Swashplate Collective Control Direction

Note: This parameter functions identically to H_SW_COL_DIR.

H_SW2_H3_ENABLE

Default 0
Range 0 1

Swashplate 2 Type (H_SW2_H3_ENABLE)

Description

H_SW2_H3_ENABLE configures the physical servo layout for the second rotor on a Dual-Rotor helicopter (Tandem, Coaxial, or Intermeshing).

  • 0: Non-CCPM (Standard separate servos).
  • 1: H3-120 (3 servos arranged at 120-degree intervals).

Tuning & Behavior

  • Default Value: 0.
  • Recommendation: Match the physical layout of your second swashplate.

H_SW2_H3_PHANG

deg
Default 0
Range -30 30

Swashplate 2 Phase Angle (H_SW2_H3_PHANG)

Description

H_SW2_H3_PHANG corrects the timing of the second rotor's control inputs.

Because of gyroscopic precession, pushing the swashplate "Forward" doesn't always make the blades tilt "Forward." This parameter adds an offset (Lead/Lag) to align the physical tilt with the intended movement.

Tuning & Behavior

  • Default Value: 0.
  • Tuning: Hover the heli and push the Pitch stick. If the heli also rolls, adjust this value until the roll component is gone.

H_SW2_H3_SV1_POS

m
Default 0.0f
Range -5 5

Antenna Z position offset

Note: This parameter functions identically to H_SW_H3_SV1_POS.

H_SW2_H3_SV2_POS

m
Default 0.0f
Range -5 5

Antenna Z position offset

Note: This parameter functions identically to H_SW_H3_SV2_POS.

H_SW2_H3_SV3_POS

m
Default 0.0f
Range -5 5

Antenna Z position offset

Note: This parameter functions identically to H_SW_H3_SV3_POS.

H_SW2_LIN_SVO

null
Default 0
Range null

Linearize Swashplate Servo Mechanical Throw

Note: This parameter functions identically to H_SW_LIN_SVO.

H_SW2_TYPE

null
Default TILT_TYPE_CONTINUOUS
Range null

Tiltrotor type

Note: This parameter functions identically to H_SW_TYPE.

H_SW_H3_ENABLE

Default 0
Range 0 1

H3 Swashplate Enable (H_SW_H3_ENABLE)

Description

H_SW_H3_ENABLE activates advanced setup for 3-servo (H3) swashplates.

Normally, ArduPilot assumes a standard 120° swashplate layout. If your helicopter has a custom mechanical layout where the servos are not at the standard positions, you enable this parameter to manually define the angle of each servo using H_SW_H3_SV1_POS etc.

  • 0: Default. Use the layout selected in H_SW_TYPE.
  • 1: Manual. Use custom servo angles.

H_SW_H3_PHANG

deg
Default 0
Range -30 30

H3 Generic Phase Angle Comp (H_SW_H3_PHANG)

Description

H_SW_H3_PHANG corrects for "Control Coupling" – a common issue on helicopters where a pitch command causes a roll, or vice versa.

Because of gyroscopic precession, a force applied to the main rotor blades takes effect 90 degrees later in the rotation. If your swashplate linkages are not perfectly aligned with the blade grips, the drone will "drift" sideways when you tell it to go forward. This parameter rotates the virtual control axes to fix that alignment error.

Tuning & Behavior

  • Default Value: 0.
  • Tuning: If you push the pitch stick forward and the heli rolls to the right, add a few degrees of phase angle until the movement is purely longitudinal.

H_SW_H3_SV1_POS

deg
Default -60
Range -180 180

H3 Servo 1 Position (H_SW_H3_SV1_POS)

Description

H_SW_H3_SV1_POS defines the physical location of the first swashplate servo on a 3-servo head.

Angles are measured from the nose (0°).

  • -60: Standard position for many RC helicopters (Rear-Left).
  • 60: Standard position (Rear-Right).
  • 180: Standard position (Front).

Tuning & Behavior

H_SW_H3_SV2_POS

deg
Default 120
Range -180 180

Swashplate Servo 2 Position (H_SW_H3_SV2_POS)

Description

H_SW_H3_SV2_POS defines the location of the second servo.

H_SW_H3_SV3_POS

deg
Default 240
Range -180 180

Swashplate Servo 3 Position (H_SW_H3_SV3_POS)

Description

H_SW_H3_SV3_POS defines the location of the third servo.

H_SW_TYPE

Default 0
Range 0 5

Swashplate Type (H_SW_TYPE)

Description

Defines the physical layout of the swashplate servos (e.g., 120-degree CCPM vs. 90-degree).

  • 0: H3 Generic (3 servos)
  • 1: H1 (Non-CCPM)
  • 3: H3_120 (Standard 120-degree layout)

H_TAIL_SPEED

%
Default 0
Range 0 100

DDVP Tail ESC speed (H_TAIL_SPEED)

Description

H_TAIL_SPEED sets the target RPM for a Direct Drive Variable Pitch (DDVP) tail.

In this setup, the tail rotor is spun by its own motor at a constant speed, while a servo changes the blade pitch to control yaw. This parameter defines how much power is sent to the tail motor ESC.

Tuning & Behavior

  • Default Value: 0.
  • Recommendation: Set high enough to ensure the tail has enough authority to counter main rotor torque during high-load maneuvers, but not so high that you waste battery or stress the motor.

H_TAIL_TYPE

Default 0
Range 0 4

Tail Type (H_TAIL_TYPE)

Description

Defines the hardware configuration used for yaw control on a single-rotor helicopter.

  • 0: Servo only (Standard mechanical tail)
  • 1: Servo with External Gyro
  • 2: DirectDrive VarPitch (Motor on tail, pitch servo controlled)
  • 3: DirectDrive FixedPitch CW (Motor speed controls yaw, clockwise rotor)
  • 4: DirectDrive FixedPitch CCW (Motor speed controls yaw, counter-clockwise rotor)

H_YAW_REV_EXPO

Default 0
Range 0 1

Yaw Reverse Exponential (H_YAW_REV_EXPO)

Description

H_YAW_REV_EXPO smooths out the tail response when the helicopter is flying backward.

H_YAW_SCALER

Default 1.0
Range 0 2

Yaw Axis Gain Scaler (H_YAW_SCALER)

Description

H_YAW_SCALER is specific to Dual Rotor helicopters (like Coaxial or Tandem designs).

It provides a master gain for the yaw axis. Because dual-rotor helis use complex torque-matching or differential pitch to yaw, the standard PID gains might not have enough range. This parameter allows you to scale the entire output to get the desired yaw rate.

Tuning & Behavior

  • Default Value: 1.0.
  • Recommendation: If the helicopter is lazy in yaw even with high P-gains, increase this to 1.5.
  • Safety: Only active for Dual Heli builds.

H_YAW_TRIM

Default 0.0
Range 0 1

Tail Rotor Trim (H_YAW_TRIM)

Description

Provides a static offset to the tail rotor output (primarily for DDFP tails) to account for constant main-rotor torque during hover.

H_SW_LIN_SVO: Linearize Swashplate Servo Mechanical Throw

Description

This linearizes the swashplate servo's mechanical output to account for nonlinear output due to arm rotation. This requires a specific setup procedure to work properly. The servo arm must be centered on the mechanical throw at the servo trim position and the servo trim position kept as close to 1500 as possible. Leveling the swashplate can only be done through the pitch links. See the ardupilot wiki for more details on setup.

Values

Value Meaning
0 Disabled
1 Enabled

Description

Enables compensation for the non-linear mechanical movement of rotary servo arms driving the swashplate. When enabled, it adjusts the servo output to produce linear swashplate movement relative to the input, provided the mechanical setup is correct (arms centered at 1500 trim).

Source Code

ardupilot/libraries/AP_Motors/AP_MotorsHeli_Swash.cpp

H_SW_COL_DIR: Swashplate Collective Control Direction

Description

Direction collective moves for positive pitch. 0 for Normal, 1 for Reversed.

Values

Value Meaning
0 Normal
1 Reversed

Description

This parameter controls the direction of collective pitch movement. It reverses the collective input to the swashplate mixing.

  • Normal (0): Standard collective direction.
  • Reversed (1): Inverted collective direction.

In the code, when set to Reversed, the collective input is inverted (collective = 1 - collective).

Source Code

ardupilot/libraries/AP_Motors/AP_MotorsHeli_Swash.cpp