MAVLink Profiles
A MAVLink profile (also called a mode) defines a set of messages that can be streamed by default on a MAVLink channel and their rates.
This section lists the profiles, and explains how they can be used and extended.
Available Profiles
The available profiles (in source-code declaration order) are:
- Normal (
MAVLINK_MODE_NORMAL): Set of messages for a GCS. - Onboard (
MAVLINK_MODE_ONBOARD): Set of messages for a companion computer on a fast link (such as Ethernet). - Gimbal (
MAVLINK_MODE_GIMBAL): Messages for a gimbal. Note this also enables message forwarding. - External Vision (
MAVLINK_MODE_EXTVISION): Messages for offboard vision systems. - External Vision Minimal (
MAVLINK_MODE_EXTVISIONMIN): Messages for offboard vision systems on slower links. - OSD (
MAVLINK_MODE_OSD): Set of messages for an OSD system. - Magic (
MAVLINK_MODE_MAGIC): No messages streamed by default. Used when configuring streaming dynamically via MAVLink. - Custom (
MAVLINK_MODE_CUSTOM): Same asMAVLINK_MODE_MAGIC. - Config (
MAVLINK_MODE_CONFIG): Set of messages for configuration interface, sent at higher rates. This is used, for example, to send theMAVLINK_MODE_NORMALmessage set via USB to a GCS. - Iridium (
MAVLINK_MODE_IRIDIUM): StreamsHIGH_LATENCY2message to an iridium satellite phone. - Minimal (
MAVLINK_MODE_MINIMAL): Minimal set of messages for use with a GCS on a poor telemetry link. - Onboard Low Bandwidth (
MAVLINK_MODE_ONBOARD_LOW_BANDWIDTH): Set of messages to be streamed to a companion computer for re-routing to a reduced-traffic link, such as a GCS. - Low Bandwidth (
MAVLINK_MODE_LOW_BANDWIDTH): Reduced message set for low bandwidth links. - uAvionix (
MAVLINK_MODE_UAVIONIX): Messages for a uAvionix ADS-B beacon. - Distance Sensor (
MAVLINK_MODE_DISTANCE_SENSOR): Streams distance sensor data at unlimited rate.
TIP
The profile defines the default messages and rates. A connected MAVLink system can still request the streams/rates it wants using MAV_CMD_SET_MESSAGE_INTERVAL.
To find the exact messages in each profile, search for configure_streams_to_default (or the above profile names) in mavlink_main.cpp.
Assigning Profiles to Ports
MAVLink Peripherals explains how to set up a port for communicating over MAVLink. This uses the concept of an abstract MAVLink instance which is then assigned to a serial port.
The profile associated with a particular MAVLink instance is set using the associated MAV_X_MODE parameter:
There are also dedicated profile parameters for ports that are not configured via MAVLink instances:
- USB_MAV_MODE: Profile for the USB port (used when MAVLink is set or detected on USB).
- MAV_S_MODE: Profile for the internal SOM (System on Module) to FMU communication channel, used on boards where the FMU and companion computer are co-located on the same module.
Note that not all profiles can necessarily be set on these ports.
Adding Messages to a Profile
You can add messages to a profile in appropriate case switch in the Mavlink::configure_streams_to_default(const char *configure_single_stream) method (see mavlink_main.cpp).
If you're testing with a GCS over USB you might add the message to the MAVLINK_MODE_CONFIG case using the configure_stream_local() method. For example, to stream BATTERY_STATUS_DEMO at 5 Hz:
cpp
case MAVLINK_MODE_CONFIG: // USB
// Note: streams requiring low latency come first
...
configure_stream_local("BATTERY_STATUS_DEMO", 5.0f);
...See Streaming MAVLink Messages for a more detailed example.