Skip to main content

Documentation Index

Fetch the complete documentation index at: https://mintlify.com/Ardupilot/ardupilot/llms.txt

Use this file to discover all available pages before exploring further.

Parameters are the primary mechanism for configuring ArduPilot behaviour at runtime without recompiling firmware. Every tunable value—from PID gains and failsafe thresholds to frame type and RC mapping—is exposed as a named parameter that persists across reboots in EEPROM or onboard flash storage. Parameters can be read and written over MAVLink, which means any connected ground control station or companion computer can change them in flight or on the bench.

How parameters are stored

ArduPilot uses the AP_Param library (libraries/AP_Param/) to manage all parameters. At the C++ level each parameter is a typed object (AP_Int8, AP_Int16, AP_Int32, AP_Float, or AP_Vector3f) that is declared as a class member and registered in a static var_info[] table using the AP_GROUPINFO macro. The library serialises these objects to a contiguous region of EEPROM or flash on write and deserialises them on boot. The maximum length of a full parameter name (including group prefixes) is 16 characters, enforced by AP_MAX_NAME_SIZE in AP_Param.h:
// libraries/AP_Param/AP_Param.h
#define AP_MAX_NAME_SIZE 16
Parameters are identified by a numeric key derived from their position in the var_info[] table. Changing the index of an existing AP_GROUPINFO entry without incrementing the layout version number (k_format_version) will silently corrupt the stored value for that parameter on existing vehicles.

Parameter types

C++ typeMAVLink typeDescription
AP_Int8MAV_PARAM_TYPE_INT8Signed 8-bit integer
AP_Int16MAV_PARAM_TYPE_INT16Signed 16-bit integer
AP_Int32MAV_PARAM_TYPE_INT32Signed 32-bit integer
AP_FloatMAV_PARAM_TYPE_REAL3232-bit IEEE float
AP_Vector3f— (sent as three floats)3D vector (x/y/z)
AP_Enum<T> is a thin wrapper around AP_Int8 or AP_Int16 that enforces a C++ enum type, giving type safety while still sending the underlying integer over MAVLink.

AP_Param C++ annotations

Every parameter entry in a var_info[] table is preceded by a block of // comments using @ annotation tags. These annotations are parsed by the ArduPilot documentation generator and by ground station software to provide human-readable names, descriptions, and constraints.
AnnotationPurpose
@ParamShort parameter name (matches the string in AP_GROUPINFO)
@DisplayNameHuman-readable name shown in GCS parameter lists
@DescriptionDetailed description of what the parameter controls
@ValuesComma-separated value:label pairs for discrete options
@BitmaskComma-separated bit:label pairs for bitmask parameters
@RangeMinimum and maximum allowed values (min max)
@UnitsSI or domain unit string (m, Hz, deg, s, PWM, etc.)
@IncrementSuggested UI step size
@UserAudience: Standard (shown by default) or Advanced
@RebootRequiredTrue if the vehicle must be rebooted for the change to take effect

Real example from ArduCopter/Parameters.cpp

The following block defines FS_THR_ENABLE, the RC throttle failsafe enable parameter. It demonstrates the full set of annotations alongside the GSCALAR macro that registers the parameter:
// @Param: FS_THR_ENABLE
// @DisplayName: Throttle Failsafe Enable
// @Description: The throttle failsafe allows you to configure a software
//   failsafe activated by a setting on the throttle input channel
// @Values: 0:Disabled,1:Enabled always RTL,3:Enabled always Land,
//   4:Enabled always SmartRTL or RTL,5:Enabled always SmartRTL or Land,
//   6:Enabled Auto DO_LAND_START/DO_RETURN_PATH_START or RTL,
//   7:Enabled always Brake or Land
// @User: Standard
GSCALAR(failsafe_throttle, "FS_THR_ENABLE",
        static_cast<float>(FS_THR_Action::ALWAYS_RTL)),
And a float parameter with range and units:
// @Param: FS_THR_VALUE
// @DisplayName: Throttle Failsafe Value
// @Description: The PWM level in microseconds on channel 3 below which
//   throttle failsafe triggers
// @Range: 910 1100
// @Units: PWM
// @Increment: 1
// @User: Standard
GSCALAR(failsafe_throttle_value, "FS_THR_VALUE", FS_THR_VALUE_DEFAULT),
A parameter requiring reboot:
// @Param: FRAME_TYPE
// @DisplayName: Frame Type (+, X, V, etc)
// @Description: Controls motor mixing for multicopters.
// @Values: 0:Plus, 1:X, 2:V, 3:H, ...
// @User: Standard
// @RebootRequired: True
GSCALAR(frame_type, "FRAME_TYPE", HAL_FRAME_TYPE_DEFAULT),

User levels: Standard vs Advanced

The @User annotation has two values:
  • Standard — shown by default in most GCS parameter views. These are the parameters most users will need to configure.
  • Advanced — hidden by default. Users must explicitly enable “show advanced parameters” to see and edit them.
Setting a parameter to Advanced signals that incorrect values can degrade vehicle performance or safety, and that the default value is suitable for most users.

@RebootRequired parameters

Parameters tagged @RebootRequired: True are applied only when the vehicle boots. Changing them over MAVLink will succeed (the new value is stored to EEPROM), but the change will not take effect until the next power cycle or software reset. Examples include FRAME_TYPE, BRD_TYPE, and serial port protocol assignments.
Do not reboot the vehicle in flight to apply a @RebootRequired parameter change. Plan these changes on the ground before arming.

Viewing and setting parameters

MAVProxy

MAVProxy is the command-line GCS used for development and scripting. Common parameter commands:
# List all parameters matching a pattern
param show FS_*

# Fetch the complete parameter list from the vehicle
param fetch

# Set a single parameter
param set FS_THR_ENABLE 1

# Save the current parameter set to a local file
param save my_params.parm

# Load parameters from a file
param load my_params.parm

Mission Planner / QGroundControl

Both ground stations provide a graphical parameter editor. Parameters are grouped by prefix (e.g. ARMING_, INS_, EKF3_). The @DisplayName and @Description annotations populate the tooltip text. Parameters can also be changed directly using the MAVLink PARAM_SET message:
PARAM_SET {
  target_system: 1,
  target_component: 1,
  param_id: "FS_THR_ENABLE",   // null-padded to 16 bytes
  param_value: 1.0,             // always a float on the wire
  param_type: MAV_PARAM_TYPE_INT8
}
The vehicle responds with a PARAM_VALUE message echoing the new value, confirming the write succeeded. If the parameter does not exist or the value is out of range the vehicle sends the unchanged current value.
All parameter values are transmitted as float over MAVLink regardless of their underlying C++ type. The param_type field tells the receiver how to interpret the float bits.

AP_GROUPINFO macro

Parameters that belong to a class (rather than the top-level vehicle) are registered using AP_GROUPINFO. The macro arguments are:
AP_GROUPINFO("SHORT_NAME", index, ClassName, member_variable, default_value)
  • "SHORT_NAME" — the suffix appended to the group prefix to form the full parameter name
  • index — a unique non-negative integer within this group; never reuse or reorder these
  • ClassName — the class owning the parameter
  • member_variable — the class member of AP_* type
  • default_value — the value used when no stored value is found
Example from ArduCopter/mode_rtl.cpp:
AP_GROUPINFO("ALT_M", 1, ModeRTL, altitude_m, RTL_ALT_M_DEFAULT),
AP_GROUPINFO("ALT_FINAL_M", 2, ModeRTL, alt_final_m, RTL_ALT_FINAL_M_DEFAULT),
AP_GROUPINFO("CLIMB_MIN_M", 3, ModeRTL, climb_min_m, RTL_CLIMB_MIN_M_DEFAULT),
AP_GROUPINFO("SPEED_MS", 4, ModeRTL, speed_ms, 0),
The group prefix RTL_ is set when the group is added to the parent class, producing full names like RTL_ALT_M and RTL_SPEED_MS.
Use param show in MAVProxy after connecting to a vehicle to see every parameter’s current value alongside its full name. This is the fastest way to verify a parameter write succeeded.

Build docs developers (and LLMs) love