MAVLINKHUD

Overview

The PUP parameter group configures the Pullup library for ArduPlane. This is an advanced safety feature designed for high-altitude aircraft or specialized drop-launch missions (where the plane is dropped from another vehicle).

The pullup logic handles the transition from a vertical freefall or steep dive into stable level flight without exceeding the structural G-load limits of the airframe.

Key Concepts

1. Freefall Recovery

When a plane is dropped, it has no initial airspeed and the control surfaces are ineffective.

  • PUP_ENABLE: Master switch.
  • PUP_ARSPD_START: The airspeed (m/s) the autopilot must reach before it attempts to pull the nose up.

2. G-Load Protection (PUP_NG_LIM)

Pulling up too sharply at high speed can snap the wings.

  • PUP_NG_LIM: Sets the maximum vertical G-load (in Gs) allowed during the recovery maneuver. The autopilot will modulate the elevator to stay within this limit.

Parameter Breakdown

  • PUP_PITCH_START: The pitch angle at which the system starts the pullup logic.
  • PUP_ELEV_OFS: A constant elevator offset used to initiate the nose-up movement.

Integration Guide

  • Special Missions: This is primarily used for atmospheric research drones or high-altitude balloon launches.
  • Simulation: Test in SITL drop-launch scenarios before attempting a real drop mission.

Developer Notes

  • Library: ArduPlane/pullup.cpp.

PUP_ENABLE: Enable pullup after altitude wait

Description

Enable pullup after altitude wait.

Values

Value Meaning
0 Disabled
1 Enabled
  • Default: 0

Description

This parameter activates the special "Pull-Up" sequence for high-altitude glider drops (e.g., from a balloon).

  • Function: When the mission command NAV_ALTITUDE_WAIT completes (meaning the balloon has burst or the release altitude is reached), the plane will execute a controlled pull-up maneuver to transition from a vertical dive to level flight without over-stressing the airframe.
  • Safety: Prevents structural failure by limiting the G-force (PUP_NG_LIM) during the recovery.

Source Code

ardupilot/ArduPlane/pullup.cpp

PUP_ARSPD_START

m/s
Default 30
Range 0 100

PUP_ARSPD_START: Pullup target airspeed

Description

Target airspeed for initial airspeed wait.

Values

  • Range: 0 to 100
  • Units: m/s
  • Default: 30

Description

This parameter sets the Minimum Airspeed Trigger for the pull-up maneuver.

  • Function: If an airspeed sensor is available, the autopilot will wait until the vehicle reaches this speed during the freefall before attempting to pull up.
  • Purpose: Prevents stalling the control surfaces. The control surfaces need airflow to be effective; pulling up at 0 airspeed does nothing but stall the servos.

PUP_ELEV_OFS

%
Default 0
Range -1.0 1.0

PUP_ELEV_OFS: Elevator deflection used before starting pullup

Description

Elevator deflection offset from -1 to 1 while waiting for airspeed to rise before starting close loop control of the pullup.

Values

  • Range: -1.0 to 1.0
  • Units: % (Normalized)
  • Default: 0

Description

This parameter applies a fixed elevator offset during the "Freefall" phase.

  • Function: While the aircraft is diving to gain speed (before the high-G pull-up begins), this offset is applied to the elevator.
  • Usage: Typically set to 0. Can be used to trim the aircraft for a specific dive angle if it has a tendency to pitch up or down naturally.

PUP_NG_JERK_LIM

1/s
Default 5.0
Range 1.0 10.0

PUP_NG_JERK_LIM: Maximum normal load factor rate of change during pullup

Description

The maximum rate of change of normal load factor (Jerk) allowed during the pullup maneuver.

Values

  • Range: 1.0 to 10.0
  • Units: 1/s
  • Default: 5.0

Description

This parameter controls how smoothly the G-force is applied.

  • Function: Instead of snapping instantly from 1G to 4G (which could snap the wing spar), this parameter ramps the G-load up gradually.
  • Physics: It limits the "Jerk" (the derivative of acceleration).
  • Effect: A lower value makes the onset of the pull-up smoother but takes longer to reach the maximum turn rate, requiring more altitude. A higher value initiates the turn faster but puts a sudden shock load on the airframe.

PUP_NG_LIM

G
Default 2.0
Range 1.0 4.0

PUP_NG_LIM: Maximum normal load factor during pullup

Description

This is the nominal maximum value of normal load factor used during the closed loop pitch rate control of the pullup.

Values

  • Range: 1.0 to 4.0
  • Units: G (Gravities)
  • Default: 2.0

Description

This parameter sets the G-force limit for the autonomous pull-up.

  • Function: During the recovery from a vertical dive, the autopilot calculates a pitch rate that will produce this specific Normal Acceleration (G-load).
  • Safety: It prevents the autopilot from pulling up so hard that it snaps the wings off the glider.
  • Tuning: Set this according to your airframe's structural limits (e.g., 2.0 G is generally safe for foamies, 4.0 G requires composite reinforcement).

PUP_PITCH

deg
Default 0
Range -180 180

Custom pitch (PUP_PITCH)

Description

This parameter defines the Pitch component of a custom user-defined rotation. It is part of the CUSTOM_ORIENTATION system, allowing you to define arbitrary sensor mounting angles that do not fit the standard 90-degree increments (e.g., a GPS mounted on a 15-degree slope).

The Mathematics

The rotation is applied as an intrinsic Euler sequence (Yaw -> Pitch -> Roll).
$$ R\_{\text{total}} = R\_z(\text{PUP\_YAW}) \cdot R\_y(\text{PUP\_PITCH}) \cdot R\_x(\text{PUP\_ROLL}) $$

The Engineer's View

Defined in libraries/AP_CustomRotations/AP_CustomRotations_params.cpp.

Tuning & Behavior

  • Default Value: 0 deg
  • Usage: Set AHRS_ORIENTATION (or sensor specific orientation) to 100 (Custom) to use these values.

PUP_PITCH_START

deg
Default -60
Range -80 0

PUP_PITCH_START: Pullup target pitch

Description

Target pitch for initial pullup.

Values

  • Range: -80 to 0
  • Units: deg
  • Default: -60

Description

This parameter defines the Pitch Angle Trigger for the pull-up maneuver.

  • Function: After the altitude wait finishes (e.g., balloon burst), the autopilot assumes the vehicle is tumbling or diving vertically. It waits for the nose to stabilize at this pitch angle (e.g., -60 degrees, nose down) before initiating the high-G pull-up.
  • Purpose: Ensures the aircraft has gained sufficient airspeed and aerodynamic authority before attempting to pull out of the dive.