PARAM_REQUEST_READ
Summary
The PARAM_REQUEST_READ message is used by a Ground Control Station (GCS) to request the current value of a specific onboard parameter. ArduPilot supports looking up parameters either by their index (offset in the list) or by their 16-character string ID.
Status
Supported
Directionality
- TX (Transmit): None
- RX (Receive): All Vehicles (Requests a
PARAM_VALUEreply)
Reception (RX)
Reception is handled by GCS_MAVLINK::handle_param_request_read in libraries/GCS_MAVLink/GCS_Param.cpp:225.
Architecture: Asynchronous Lookup
ArduPilot does not look up the parameter immediately upon receipt to avoid blocking the main loop.
- Queueing: The handler decodes the message and pushes a request into a
pending_param_requestqueue. - Processing: A background IO timer (
GCS_MAVLINK::param_io_timer) pops the request. - Lookup:
- By Index: If
param_indexis not-1, it usesAP_Param::find_by_index. - By ID: If
param_indexis-1, it usesAP_Param::findwith theparam_idstring.
- By Index: If
- Response: If found, the result is queued for transmission as a
PARAM_VALUEmessage.
Data Fields
target_system: System ID.target_component: Component ID.param_id: Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string.param_index: Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored).
Practical Use Cases
- Single Parameter Refresh:
- Scenario: A user changes a PID value and wants to verify it was written correctly.
- Action: The GCS sends
PARAM_REQUEST_READforATC_RAT_RLL_Pto confirm the new value.
- Lazy Loading:
- Scenario: A mobile GCS wants to show a "Battery Settings" page but doesn't want to download all 1000+ parameters on connection.
- Action: It requests only the specific parameters needed for that page (e.g.,
BATT_MONITOR,BATT_CAPACITY) on demand.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Param.cpp:225: Contains
handle_param_request_readand the asyncparam_io_timer.
PARAM_REQUEST_LIST
Summary
The PARAM_REQUEST_LIST message triggers a bulk transfer of all onboard parameters. This is the primary "handshake" event when a Ground Control Station (GCS) connects to the vehicle, allowing it to download the full configuration state (typically 1000+ parameters).
Status
Supported
Directionality
- TX (Transmit): Specific Peripherals (ArduPilot acts as a GCS to a Gimbal)
- RX (Receive): All Vehicles (Triggers bulk download)
Reception (RX)
Reception is handled by GCS_MAVLINK::handle_param_request_list in libraries/GCS_MAVLink/GCS_Param.cpp:206.
Streaming Architecture
ArduPilot handles the massive task of sending all parameters without blocking the main flight loop using a deferred state machine:
- Initialization: The handler resets the internal cursor (
_queued_parameter) to the first parameter index. - Scheduling: It does not loop immediately. Instead, it relies on the GCS scheduler (
try_send_message). - Iteration: In subsequent main loop cycles, the scheduler calls
queued_param_send. - Rate Limiting:
queued_param_sendis highly sophisticated:- It checks available bandwidth (
bw_in_bytes_per_second). - It enforces a 1ms execution time limit per burst to prevent CPU starvation.
- It temporarily slows down other telemetry streams (by 4x) to prioritize the parameter download.
- It checks available bandwidth (
Transmission (TX)
Interestingly, ArduPilot can also act as a client for this message.
- Solo Gimbal: In libraries/AP_Mount/SoloGimbal_Parameters.cpp, ArduPilot sends
PARAM_REQUEST_LISTto a connected Solo Gimbal to learn its configuration.
Data Fields
target_system: System ID.target_component: Component ID.
Practical Use Cases
- Initial Connection:
- Scenario: A pilot connects Mission Planner to the drone via USB.
- Action: Mission Planner sends
PARAM_REQUEST_LIST. The green bar loads as ArduPilot streams ~1200PARAM_VALUEmessages back.
- Backup/Restore:
- Scenario: A user wants to save a "Known Good" config file.
- Action: The GCS requests the list and saves the results to a
.paramfile.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Param.cpp:206: Contains
handle_param_request_listand thequeued_param_sendstate machine.
PARAM_VALUE
Summary
The PARAM_VALUE message is the fundamental unit of configuration data in MAVLink. It carries the name (param_id), value (as a float), and type of a single onboard parameter. It is primarily sent by the vehicle in response to read/list requests, but ArduPilot also receives it when acting as a GCS for smart peripherals (like Gimbals).
Status
Supported
Directionality
- TX (Transmit): All Vehicles (Streams configuration to GCS)
- RX (Receive): Specific Peripherals (Receives configuration from Gimbal)
Transmission (TX)
The transmission logic is centered in libraries/GCS_MAVLink/GCS_Param.cpp.
Encoding Logic
- Storage vs. Protocol: Internally, ArduPilot stores parameters as
int8,int16,int32, orfloat. MAVLink 1.0/common only supports passing values asfloat. - Conversion:
AP_Param::cast_to_float()is used to convert integer parameters into the float field of the message. This works because a 32-bit float can exactly represent all 16-bit integers and most relevant 32-bit integers. - Type Hinting: The message includes a
param_typefield (e.g.,MAV_PARAM_TYPE_INT32). A smart GCS uses this to cast the float back to the correct integer type for display.
Senders
queued_param_send: In GCS_Param.cpp:41, the background stream used forPARAM_REQUEST_LIST.send_parameter_async_replies: Used forPARAM_REQUEST_READreplies.handle_param_set: In GCS_Param.cpp:263, immediate echo-back when a parameter is written.
Reception (RX)
ArduPilot handles this message in GCS_MAVLINK::handle_param_value within libraries/GCS_MAVLink/GCS_Common.cpp:821.
Usage
It delegates the message to the AP_Mount library.
- Scenario: A 3DR Solo Gimbal is connected.
- Behavior: The gimbal sends its own parameters to the autopilot.
SoloGimbal_Parameters::handle_param_valueparses these to populate its internal state, allowing the autopilot to "know" the gimbal's tuning.
Data Fields
param_id: Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string.param_value: Onboard parameter value.param_type: Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.param_count: Total number of onboard parameters.param_index: Index of this onboard parameter.
Practical Use Cases
- Configuration Display:
- Scenario: A GCS receives
PARAM_VALUEforRTL_ALTwith value1500.0. - Action: It displays "Return Altitude: 15m" (1500cm).
- Scenario: A GCS receives
- Verification:
- Scenario: A script sets a parameter.
- Action: It waits for the
PARAM_VALUEbroadcast to confirm the autopilot accepted and applied the change.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Param.cpp:41: Primary TX logic (streaming).
- libraries/GCS_MAVLink/GCS_Common.cpp:821: Entry point for received
PARAM_VALUE. - libraries/AP_Mount/SoloGimbal_Parameters.cpp: Client-side RX logic for gimbals.
PARAM_SET
Summary
The PARAM_SET message is the standard way to modify vehicle configuration over MAVLink. It allows a Ground Control Station (GCS) to write a new value to a specific parameter identified by its string ID. ArduPilot handles these requests by updating the internal parameter state and committing the change to non-volatile storage (EEPROM/Flash).
Status
Supported
Directionality
- TX (Transmit): None
- RX (Receive): All Vehicles (Modifies configuration)
Reception (RX)
Reception is handled by GCS_MAVLINK::handle_param_set in libraries/GCS_MAVLink/GCS_Param.cpp:263.
Processing Logic
- Lookup: The autopilot identifies the parameter by its 16-character name.
- Safety Check: It verifies if the parameter allows modification via MAVLink using
allow_set_via_mavlink.- If denied (e.g., a read-only hardware ID), ArduPilot sends a
PARAM_VALUEmessage containing the original value as an implicit NACK.
- If denied (e.g., a read-only hardware ID), ArduPilot sends a
- Validation: It rejects
NaNorInfvalues. - Update: The internal value is updated via
set_float. - Persistence: The change is saved to storage via
vp->save(). - Notification: ArduPilot broadcasts a
PARAM_VALUEmessage to all active channels to confirm the change. This is triggered by theGCS_SEND_PARAMmacro in libraries/AP_Param/AP_Param.cpp.
Data Fields
target_system: System ID.target_component: Component ID.param_id: Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string.param_value: Onboard parameter value.param_type: Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
Practical Use Cases
- Field Tuning:
- Scenario: A pilot notices the drone is oscillating in flight.
- Action: The GCS sends
PARAM_SETforATC_RAT_RLL_Pwith a lower value. The drone applies it immediately, and the pilot observes the result.
- Mission Configuration:
- Scenario: Before a flight, the GCS sets
RTL_ALTto 50m to avoid tall trees at the specific site. - Action: ArduPilot saves the value to Flash, ensuring it persists across reboots.
- Scenario: Before a flight, the GCS sets
- Component Integration:
- Scenario: A companion computer enables a new feature (e.g., Obstacle Avoidance) by setting
OA_TYPEto 1. - Action: ArduPilot re-initializes the Avoidance subsystem upon receiving the parameter change.
- Scenario: A companion computer enables a new feature (e.g., Obstacle Avoidance) by setting
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Param.cpp:263: Main entry point for writing parameters.
- libraries/AP_Param/AP_Param.cpp: Implements the
GCS_SEND_PARAMbroadcast logic.
PARAM_MAP_RC
Summary
Bind a parameter to an RC channel.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message. Parameter tuning via RC channels is handled internally via the TUNE parameter and RCx_OPTION settings, not via this MAVLink message.
Theoretical Use Cases
Dynamic parameter tuning via RC.
PARAM_EXT_REQUEST_READ
Summary
The PARAM_EXT_REQUEST_READ message is part of the MAVLink Extended Parameter Protocol. This protocol was designed to overcome limitations of the original parameter protocol (e.g., small index size, lack of type safety for strings/arrays).
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message.
ArduPilot relies on the robust and widely supported standard parameter protocol (PARAM_REQUEST_READ, PARAM_VALUE). For large datasets or complex configuration, it utilizes the MAVLink FTP (FILE_TRANSFER_PROTOCOL) to transfer parameter files or logs, rather than the intermediate Extended Parameter Protocol.
Intended Data Fields (Standard)
target_system/target_component: Targeted component.param_id: Parameter id, terminated by NULL if the length is less than 16 human-readable chars.param_index: Parameter index. Set to -1 to use theparam_id.
Theoretical Use Cases
- Exceeding 65k Parameters:
- Scenario: A massive system with more than 65,535 parameters (the limit of the standard protocol's
int16index). - Action: The Extended Protocol allows for larger indices, enabling access to the full parameter set.
- Scenario: A massive system with more than 65,535 parameters (the limit of the standard protocol's
- Long String Parameters:
- Scenario: Storing a long URL or API key as a parameter.
- Action: The standard protocol is limited to 4 bytes (float/int32). The Extended Protocol supports variable-length types, allowing full strings to be read natively.
PARAM_EXT_REQUEST_LIST
Summary
The PARAM_EXT_REQUEST_LIST message is used to request a full list of parameters from a component using the MAVLink Extended Parameter Protocol.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message.
ArduPilot uses PARAM_REQUEST_LIST (21) for listing parameters.
Intended Data Fields (Standard)
target_system/target_component: Targeted component.
Theoretical Use Cases
- High-Latency Links:
- Scenario: Syncing parameters over a very slow satellite link.
- Action: The Extended Protocol can be more efficient for specific data types, potentially reducing the overhead compared to the standard protocol's float conversions.
- Type Safety:
- Scenario: A GCS wants to ensure it never misinterprets a bitmask as a float.
- Action: The Extended Protocol explicitly carries type information for every parameter, eliminating ambiguity during the sync process.
PARAM_EXT_VALUE
Summary
The PARAM_EXT_VALUE message is the response to a PARAM_EXT_REQUEST_READ or PARAM_EXT_REQUEST_LIST request. It contains the value of a parameter in the Extended Parameter Protocol format.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message.
ArduPilot uses PARAM_VALUE (22) for parameter values.
Intended Data Fields (Standard)
param_id: Parameter id.param_value: Parameter value (up to 128 bytes).param_type: Parameter type (MAV_PARAM_EXT_TYPE).param_count: Total number of parameters.param_index: Index of this parameter.
Theoretical Use Cases
- Transferring Structs:
- Scenario: Configuring a complex fence boundary defined by a struct.
- Action: The 128-byte payload of
PARAM_EXT_VALUEallows transmitting small structures or arrays as a single atomic parameter update, rather than breaking them into 32 separate float parameters.
- 64-bit Integers:
- Scenario: Storing a precise 64-bit timestamp or large integer counter.
- Action: The standard protocol truncates to 32-bit floats (lossy).
PARAM_EXT_VALUEsupportsuint64natively.
PARAM_EXT_SET
Summary
The PARAM_EXT_SET message is used to set the value of a parameter using the MAVLink Extended Parameter Protocol.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message.
ArduPilot uses PARAM_SET (23) for setting parameter values.
Intended Data Fields (Standard)
target_system/target_component: Targeted component.param_id: Parameter id.param_value: Parameter value (up to 128 bytes).param_type: Parameter type (MAV_PARAM_EXT_TYPE).
Theoretical Use Cases
- Atomic Configuration:
- Scenario: Setting an IP address.
- Action: Instead of setting 4 separate octet parameters, the GCS sends one
PARAM_EXT_SETwith the full string "192.168.1.50", ensuring the IP doesn't become invalid in the middle of the update process.
- 64-bit Precision:
- Scenario: Setting a precise UTC time offset.
- Action: Sending a
int64value directly ensures no precision is lost to floating-point representation.
PARAM_EXT_ACK
Summary
The PARAM_EXT_ACK message is a response to a PARAM_EXT_SET command in the MAVLink Extended Parameter Protocol, indicating success or failure.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message.
ArduPilot uses the standard PARAM_VALUE broadcast as an implicit acknowledgement of a PARAM_SET.
Intended Data Fields (Standard)
param_id: Parameter id.param_value: Parameter value.param_type: Parameter type.param_result: Result code (PARAM_ACK_ACCEPTED,PARAM_ACK_VALUE_UNSUPPORTED, etc.).
Theoretical Use Cases
- Explicit Error Handling:
- Scenario: A user tries to set a parameter to an invalid value.
- Action: The standard protocol just ignores it (or maybe sends a
STATUSTEXT).PARAM_EXT_ACKallows the drone to reply withPARAM_ACK_VALUE_UNSUPPORTED, giving the GCS immediate, programmatic feedback that the write failed.
- Transaction Confirmation:
- Scenario: Automated configuration script.
- Action: The script waits for
PARAM_EXT_ACKwithPARAM_ACK_ACCEPTEDbefore proceeding to the next step, ensuring robust configuration sequence.