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.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.
How parameters are stored
ArduPilot uses theAP_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:
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++ type | MAVLink type | Description |
|---|---|---|
AP_Int8 | MAV_PARAM_TYPE_INT8 | Signed 8-bit integer |
AP_Int16 | MAV_PARAM_TYPE_INT16 | Signed 16-bit integer |
AP_Int32 | MAV_PARAM_TYPE_INT32 | Signed 32-bit integer |
AP_Float | MAV_PARAM_TYPE_REAL32 | 32-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 avar_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.
| Annotation | Purpose |
|---|---|
@Param | Short parameter name (matches the string in AP_GROUPINFO) |
@DisplayName | Human-readable name shown in GCS parameter lists |
@Description | Detailed description of what the parameter controls |
@Values | Comma-separated value:label pairs for discrete options |
@Bitmask | Comma-separated bit:label pairs for bitmask parameters |
@Range | Minimum and maximum allowed values (min max) |
@Units | SI or domain unit string (m, Hz, deg, s, PWM, etc.) |
@Increment | Suggested UI step size |
@User | Audience: Standard (shown by default) or Advanced |
@RebootRequired | True if the vehicle must be rebooted for the change to take effect |
Real example from ArduCopter/Parameters.cpp
The following block definesFS_THR_ENABLE, the RC throttle failsafe enable parameter. It demonstrates the full set of annotations alongside the GSCALAR macro that registers the parameter:
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.
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.
Viewing and setting parameters
MAVProxy
MAVProxy is the command-line GCS used for development and scripting. Common parameter commands: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.
MAVLink PARAM_SET message
Parameters can also be changed directly using the MAVLinkPARAM_SET message:
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 usingAP_GROUPINFO. The macro arguments are:
"SHORT_NAME"— the suffix appended to the group prefix to form the full parameter nameindex— a unique non-negative integer within this group; never reuse or reorder theseClassName— the class owning the parametermember_variable— the class member ofAP_*typedefault_value— the value used when no stored value is found
ArduCopter/mode_rtl.cpp:
RTL_ is set when the group is added to the parent class, producing full names like RTL_ALT_M and RTL_SPEED_MS.