Parameter Protocol

The parameter microservice is used to exchange configuration settings between MAVLink components.

Each parameter is represented as a key/value pair. The key is usually the human-readable name of the parameter (maximum of 16 characters) and a value - which can be one of a number of types.

The key/value pair has a number of important properties:

  • The human-readable name is small but useful (it can encode parameter names from which users can infer the purpose of the parameter).
  • Unknown autopilots that implement the protocol can be supported "out of the box".
  • A GCS does not have to know in advance what parameters exist on a remote system (although in practice a GCS can provide a better user experience with additional parameter metadata like maximum and minimum values, default values, etc.).
  • Adding a parameter only requires changes to the system with parameters. A GCS that loads the parameters, and the MAVLink communication libraries, should not require any changes.

Message/Enum Summary

MessageDescription
PARAM_REQUEST_LISTRequest all parameters. The recipient broadcast all parameter values using PARAM_VALUE.
PARAM_REQUEST_READRequest a single parameter. The recipient broadcasts the specified parameter value using PARAM_VALUE.
PARAM_SETSend command to set a specified parameter to a value. After the value has been set (whether successful or not), the recipient should broadcast the current value using PARAM_VALUE.
PARAM_VALUEThe current value of a parameter, broadcast in response to a request to get one or more parameters (PARAM_REQUEST_READ, PARAM_REQUEST_LIST) or whenever a parameter is set (PARAM_SET) or changes.
EnumDescription
MAV_PARAM_TYPEPARAM_SET and PARAM_VALUE store/encode parameter values within a float field. This type conveys the real type of the encoded parameter value, e.g. MAV_PARAM_TYPE_UINT16, MAV_PARAM_TYPE_INT32, etc.
FlagsDescription
MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISEParameter values are byte-wise encoded in the PARAM_SET.param_value and PARAM_VALUE.param_value fields (float).
MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CASTParameter values are encoded using C casts into the PARAM_SET.param_value and PARAM_VALUE.param_value fields (float).

Protocol Discovery

Support for the parameter protocol is indicated if either MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISE or MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST protocol bits are set in AUTOPILOT_VERSION.capabilities.

These protocol bits indicate different bytewise and C-style parameter value encoding respectively.

The protocol may still be supported even if neither protocol bit is set. To use the protocol in this case, a connected system would need to have prior knowledge of connected component.

Parameter Names

Parameters names/ids are set in the param_id field of messages where they are used. The param_id string can store up to 16 characters. The string is terminated with a NULL (\0) character if there are less than 16 human-readable chars, and without a null termination byte if the length is exactly 16 chars.

Parameter Encoding

Parameter values are encoded in the param_value field, an IEE754 single-precision, 4 byte, floating point value (see PARAM_SET and PARAM_VALUE). The param_type (MAV_PARAM_TYPE) is used to indicate the actual type of the data, so that it can be decoded by the recipient. Supported types are: 8, 16, 32 and 64-bit signed and unsigned integers, and 32 and 64-bit floating point numbers.

Two encoding approaches are supported:

  • Byte-wise encoding: The parameter's bytes are copied directly into the bytes used for the field. A 32-bit integer is sent as 32 bits of data.
  • C-style cast: The parameter value is converted to a float. This may result in some loss of precision as a float can represent an integer with up to 24 bits of pecision.

Byte wise encoding is recommended as it allows very large integers to be exchanged (e.g. 1E7 scaled integers can be useful for encoding some types of data, but lose precision if cast directly to floats).

A component should support only one type, and indicate that type by setting the MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISE (byte-wise encoding) or MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST (C-style encoding) protocol bits in AUTOPILOT_VERSION.capabilities. A GCS may support both types and use the type that is indicated by the target component.

Bytewise Encoding: Mavgen C API

The C API provides a convenient union that allows you to bytewise convert between any of the supported types: mavlink_param_union_t (mavlink_types.h). For example, below we shown how you can set the union integer field, and then pass the float value to the sending function:

mavlink_param_union_t param;
int32_t integer = 20000;
param.param_int32 = integer;
param.type = MAV_PARAM_TYPE_INT32;

// Then send the param by providing the float bytes to the send function
mavlink_msg_param_set_send(xxx, xxx, param.param_float, param.type, xxx);

Bytewise Encoding: Mavgen Python API

Pymavlink does not include special support to byte-wise encode the non-float data types (unsurprisingly, because Python effectively "hides" low level data types from users). When working with a system that supports non-float parameters (e.g. PX4) you will need to do the encoding/decoding yourself when sending and receiving messages.

There is a good example of how to do this in the Pymavlink mavparm.py module (see MAVParmDict.mavset()).

Parameter Types

The allowed parameter types are given in MAV_PARAM_TYPE.

Note that not all types are supported: for example PX4 supports only INT32 and FLOAT. A GCS can infer the supported types from the parameters it is sent.

Parameter Metadata

Parameter metadata is additional information about a parameters that allow them to be safely used in a ground station. This might include a description and listing of possible values.

The Component Information Protocol has been proposed as a mechanism for getting this information directly from a vehicle.

Parameter Caching

A GCS or other component may choose to maintain a cache of parameter values for connected components/systems, in order to reduce the time required to display values and reduce MAVLink traffic.

The cache can be populated initially by first reading the full parameter list at least once, and then updated by monitoring for PARAM_VALUE messages (which are emitted whenever a parameter is written or otherwise changed).

Cache synchronisation is not guaranteed; a component may miss update messages due to parameter changes by other components.

Multi-System and Multi-Component Support

MAVLink supports multiple systems in parallel on the same link, and multiple MAVLink enabled components within a system.

Requests to get and set parameters can be sent to individual systems or components. To get a complete parameter list from a system, send the request parameter message with target_component set to MAV_COMP_ID_ALL.

All components must respond to parameter request messages addressed to their ID or the ID MAV_COMP_ID_ALL.

QGroundControl by default queries all components of the currently connected system (it sends ID MAV_COMP_ID_ALL).

Limitations

Parameters Table is Invariant

The protocol requires that the parameter set does not change during normal operation/after parameters have been read.

If a component can add parameters during (or after) initial synchronization the protocol cannot guarantee reliable/robust synchronization, because there is no way to notify that the parameter set has changed and a new sync is required.

If working with a non-compliant component, the risk of problems when working with parameters can be reduced (but not removed) if:

  • The param_id is used to read parameters where possible (the mapping of param_index to a particular parameter might change on systems where parameters can be added/removed).
  • PARAM_VALUE.param_count is monitored and the parameter set re-sychronised on change.

Parameter Synchronisation Can Fail

A GCS (or other component) that wants to cache parameters with a component and keep them synchronised, should first get all parameters, and then track any new parameter changes by monitoring for PARAM_VALUE messages (updating their internal list appropriately).

This works for the originator of a parameter change, which can resend the request if an expected PARAM_VALUE is not recieved. This approach may fail for components that did not originate the change, as they will not know about updates they do not receive (i.e. if messages are dropped).

A component may mitigate this risk by, for example, sending the PARAM_VALUE multiple times after a parameter is changed.

Parameter Operations

This section defines the state machine/message sequences for all parameter operations.

Read All Parameters

The read-all operation is started by sending the PARAM_REQUEST_LIST message. The target component must start to broadcast the parameters individually in PARAM_VALUE messages after receiving this message. The drone should allow a pause after sending each parameter to ensure that the operation doesn't consume all of the available link bandwidth (30 - 50 percent of the bandwidth is reasonable).

Mermaid sequence: Read all parameters

The sequence of operations is:

  1. GCS (client) sends PARAM_REQUEST_LIST specifying a target system/component.
    • Broadcast addresses may be used. All targeted components should respond with parameters (or ignore the request if they have none).
    • The GCS is expected to accumulate parameters from all responding systems.
    • The timeout/retry behaviour is GSC dependent.
  2. The targeted component(s) should respond, sending all parameters individually in PARAM_VALUE messages.
    • Allow breaks between each message in order to avoid saturating the link.
    • Components with no parameters should ignore the request.
  3. GCS starts timeout after each PARAM_VALUE message in order to detect when parameters are no longer being sent (that the operation has completed).

Notes:

  • The GCS/API may accumulate the received parameters for each component and can determine if any are missing/not received (PARAM_VALUE contains the total number of params and index of current param).
  • Handling of missing params is GCS-dependent. QGroundControl, for example, individually requests each missing parameter by index.
  • If a component does not any parameters then it will ignore a PARAM_REQUEST_LIST request. The sender should simply timeout (after resends) if no PARAM_VALUE is received.

Read Single Parameter

A single parameter can be read by sending the PARAM_REQUEST_READ message, as shown below:

Mermaid sequence: Read single parameter

The sequence of operations is:

  1. GCS (client) sends PARAM_REQUEST_READ specifying either the parameter id (name) or parameter index.
  2. GCS starts timeout waiting for acknowledgment (in the form of a PARAM_VALUE message).
  3. Drone responds with PARAM_VALUE containing the parameter value. This is a broadcast message (sent to all systems).

The drone may restart the sequence if the PARAM_VALUE acknowledgment is not received within the timeout.

There is no formal way for the drone to signal when an invalid parameter is requested (i.e. for a parameter name or id that does not exist). In this case the drone should emit STATUS_TEXT. The GCS may monitor for the specific notification, but will otherwise fail the request after any timeout/resend cycle completes.

Write Parameters

Parameters can be written individually by sending the parameter name and value pair to the GCS, as shown:

Mermaid Sequence: Write parameters

The sequence of operations is:

  1. GCS (client) sends PARAM_SET specifying the param name to update and its new value (also target system/component and the param type).
  2. GCS starts timout waiting for acknowledgment (in the form of a PARAM_VALUE message).
  3. Drone writes parameter and responds by broadcasting a PARAM_VALUE containing the updated parameter value to all components/systems.

    The Drone must acknowledge the PARAM_SET by broadcasting a PARAM_VALUE even if the write operation fails. In this case the PARAM_VALUE will be the current/unchanged parameter value.

  4. GCS should update the parameter cache (if used) with the new value.
  5. The GCS may restart the sequence if the expected PARAM_VALUE is not received within the timeout, or if the write operation fails (the value returned in PARAM_VALUE does not match the value set).

The command MAV_CMD_DO_SET_PARAMETER is not part of the parameter protocol. If implemented it can be used to set the value of a parameter using the enumeration of the parameter within the remote system is known (rather than the id). This has no particular advantage over the parameter protocol methods.

Implementations

PX4

PX4 is compatible with the specification:

  • Byte-wise encoding of parameters is supported. Note however that PX4 does not set MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISE (at time of writing - PX4 v1.12). See PX4-Autopilot/issues/19275
  • Only float and Int32 parameters are used.

PX4 provides an addition off-spec mechanism that allows a GCS to cache parameters. This significantly reduces ready-to-use time for the GCS if parameters have not been changed since the previous parameter sync. The way that this mechanism works is that when the list of parameters is requested, PX4 first sends a PARAM_VALUE with the param_index of INT16_MAX (in code, referred to as PARAM_HASH) containing a hash of the parameter set.

This hash is calculated by computing the MAVLink CRC32 over all param names and values (see the param_hash_check() in source here). If the GCS has a matching hash value it can immediately start using its cached parameters (rather than having to wait while all the rest of the parameters upload).

Source files:

ArduPilot

ArduPilot implements a largely compatible version of this protocol.

  • C-style encoding of parameters is supported. Note however that ArduPilot does not set MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST.

Off spec-behaviour:

  • PARAM_VALUE is not emitted after the parameter update with the new value (or the old value if update failed).

Compatible differences:

  • Parameter sets can be enabled/disabled during operation. This can invalidate the set of synchronized parameters and make access to parameters by index unreliable.
  • PARAM_SET
    • param_type in the message is ignored. The data type is obtained by checking stored type info (via name lookup).
    • The data type is used to constrain and round the received value before it is stored (as a float).

Source files:

QGroundControl

QGroundControl implements this protocol, and works with both ArduPilot and PX4.

Source files:

results matching ""

    No results matching ""