Mavlink - iNavFlight/inav GitHub Wiki

MAVLink INAV Implementation

INAV has a partial implementation of MAVLink that is intended primarily for simple telemetry and operation. It supports RC, missions, telemetry and some features such as Guided mode; but it is very different from a compliant MAVLink spec vehicle such as Pixhawk or Ardupilot and important differences exist, as such it is not 100% compatible and cannot be expected to work the same way. The standard MAVLink header library is used in compilation.

Fundamental differences from ArduPilot/PX4

  • No MAVLink parameter API: INAV sends a single stub parameter and otherwise ignores parameter traffic. Configure the aircraft through the INAV Configurator or CLI instead.
  • Limited command support: Commands that are not implemented are ignored.
  • Mission handling: uploads are rejected while armed; mission items must use MAV_FRAME_GLOBAL (RTH items use MAV_FRAME_MISSION).
  • Mode reporting: custom_mode approximates ArduPilot modes and may not match all INAV states.
  • Flow control expectations: INAV honours RADIO_STATUS.txbuf to avoid overrunning radios; without it, packets are simply paced at 20 ms intervals.
  • Half‑duplex etiquette: when half‑duplex is enabled, INAV waits one telemetry tick after any received frame before transmitting to reduce collisions.

Relevant CLI options

  • mavlink_sysid – system ID used in every outbound packet (default 1), the system will only respond/act on packets addresses to their sysid.
  • mavlink_autopilot_type – heartbeat autopilot ID (GENERIC or ARDUPILOT).
  • mavlink_version – force MAVLink v1 when set to 1.
  • Stream rates (Hz): mavlink_ext_status_rate, mavlink_rc_chan_rate, mavlink_pos_rate, mavlink_extra1_rate, mavlink_extra2_rate, mavlink_extra3_rate. Each group is polled up to 50 Hz; a rate of 0 disables the group.
  • mavlink_min_txbuffer – minimum remote TX buffer level before sending when RADIO_STATUS provides flow control.
  • mavlink_radio_type – scales RADIO_STATUS RSSI/SNR for generic, ELRS, or SiK links.

Supported Outgoing Messages

Messages are organized into MAVLink datastream groups. Each group sends one message per trigger at the configured rate:

  • SYS_STATUS: Advertises detected sensors (gyro/accel/compass, baro, pitot, GPS, optical flow, rangefinder, RC, blackbox) and whether they are healthy. Includes main loop load, battery voltage/current/percentage, and logging capability.
  • RC_CHANNELS_RAW: for v1, RC_CHANNELS_SCALED: for v2, Up to 18 input channels plus RSSI mapped to MAVLink units.
  • GPS_RAW_INT: for GNSS fix quality, HDOP/VDOP, velocity, and satellite count when a fix (or estimated fix) exists.
  • GLOBAL_POSITION_INT: couples GPS position with INAV's altitude and velocity estimates.
  • GPS_GLOBAL_ORIGIN: broadcasts the current home position.
  • ATTITUDE: Roll, pitch, yaw, and angular rates.
  • VFR_HUD: with airspeed (if a healthy pitot is available), ground speed, throttle, altitude, and climb rate.
  • HEARTBEAT: encodes arming state and maps INAV flight modes onto ArduPilot-style custom_mode: values (see mappings below).
  • BATTERY_STATUS: with per-cell voltages (cells 11‑14 in voltages_ext), current draw, consumed mAh/Wh, and remaining percentage when available.
  • SCALED_PRESSURE: for IMU/baro temperature.
  • STATUSTEXT: when the OSD has a pending system message; severity follows OSD attributes (notice/warning/critical).

Supported Incoming Messages

  • HEARTBEAT: used to detect ADS‑B participants when type is MAV_TYPE_ADSB.
  • MISSION_COUNT: starts an upload transaction (capped at NAV_MAX_WAYPOINTS).
  • MISSION_ITEM: stores waypoints; rejects uploads while armed or with unsupported frames/sequence errors.
  • MISSION_REQUEST_LIST / MISSION_REQUEST: download active mission items; returns MISSION_ACK on bad sequence.
  • MISSION_CLEAR_ALL: clears stored mission.
  • COMMAND_INT with MAV_CMD_DO_REPOSITION in
  • RC_CHANNELS_OVERRIDE passes channel values to the MAVLink serial receiver backend.
  • RADIO_STATUS updates remote TX buffer level and scales RSSI/SNR according to mavlink_radio_type (also feeds link stats for MAVLink RX receivers).
  • ADSB_VEHICLE populates the internal traffic list when ADS‑B is enabled.
  • PARAM_REQUEST_LIST elicits a stub PARAM_VALUE response so ground stations stop requesting parameters (INAV does not expose parameters over MAVLink).

Supported Commands

Limited implementation of the Command protocol.

  • COMMAND_INT:
    • MAV_CMD_DO_REPOSITION: sets the Follow Me/GCS Nav waypoint when in GCS NAV mode, supports only MAV_FRAME_GLOBAL, otherwise returns DENIED or UNSUPPORTED.

Mode mappings (INAV β†’ MAVLink/ArduPilot)

INAV encodes custom_mode to translate INAV modes to ArduPilot copter or plane modes. Modes without a clear equivalent are omitted (ENUM_END).

  • Multirotor profiles
    • ACRO / ACRO AIR β†’ ACRO
    • ANGLE / HORIZON / ANGLE HOLD β†’ STABILIZE
    • ALT HOLD β†’ ALT_HOLD
    • POS HOLD β†’ LOITER
    • POS HOLD + GCS NAV β†’ GUIDED
    • RTH β†’ RTL
    • MISSION β†’ AUTO
    • LAUNCH β†’ THROW
    • FAILSAFE β†’ RTL, LAND, or no mapping depending on failsafe phase
  • Fixed-wing profiles
    • MANUAL β†’ MANUAL
    • ACRO / ACRO AIR β†’ ACRO
    • ANGLE β†’ FBWA
    • HORIZON / ANGLE HOLD β†’ STABILIZE
    • ALT HOLD β†’ FBWB
    • RTH β†’ RTL
    • MISSION β†’ AUTO
    • CRUISE β†’ CRUISE
    • LAUNCH β†’ TAKEOFF
    • FAILSAFE β†’ RTL, AUTO, or no mapping depending on failsafe phase

Datastream groups and defaults

Default rates (Hz) are shown; adjust with the CLI keys above.

Datastream group Messages Default rate
EXTENDED_STATUS SYS_STATUS 2 Hz
RC_CHANNELS RC_CHANNELS_RAW (v1) / RC_CHANNELS_SCALED (v2) 1 Hz
POSITION GPS_RAW_INT, GLOBAL_POSITION_INT, GPS_GLOBAL_ORIGIN 2 Hz
EXTRA1 ATTITUDE 3 Hz
EXTRA2 VFR_HUD, HEARTBEAT 2 Hz
EXTRA3 BATTERY_STATUS, SCALED_PRESSURE, STATUSTEXT (when present) 1 Hz

Operating tips

  • Set mavlink_radio_type to ELRS or SiK if you use those links to get accurate link quality scaling in RADIO_STATUS.
  • If you rely on RC override via MAVLink, ensure the serial receiver type is set to SERIALRX_MAVLINK and consider enabling telemetry_halfduplex when RX shares the port.
  • To reduce bandwidth, lower the stream rates for groups you do not need, or disable them entirely by setting the rate to 0.