Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
27 commits
Select commit Hold shift + click to select a range
d6ee8e7
mavlink compatibility fixes
xznhj8129 Dec 13, 2025
9b3553f
compatibility + messages
xznhj8129 Dec 13, 2025
579f918
qgc mission errors fix + frame handling
xznhj8129 Dec 13, 2025
4682d1c
no takeoff
xznhj8129 Dec 13, 2025
6b7bdba
defaults in wps
xznhj8129 Dec 14, 2025
bd521f2
available modes fixes + unit tests
xznhj8129 Jan 17, 2026
92aaaf3
fix wrong mav version call
xznhj8129 Jan 28, 2026
d48e0cd
honor altitude frames for guided
xznhj8129 Jan 28, 2026
8c983b7
remove duplicate extended sys state
xznhj8129 Jan 28, 2026
c71550c
align heartbeat type for fixed wing
xznhj8129 Jan 28, 2026
91450ea
add mavlink protocol and guided tests
xznhj8129 Jan 28, 2026
d942755
treat guided global altitude as relative
xznhj8129 Jan 28, 2026
69655ad
reject mission upload while armed
xznhj8129 Jan 28, 2026
49b97f6
restore guided absolute altitude handling
xznhj8129 Jan 28, 2026
9f61e65
support guided mission_item_int
xznhj8129 Jan 28, 2026
592246f
map mavlink modes to box config
xznhj8129 Jan 28, 2026
b0e4fce
fix do_jump waypoint p3
xznhj8129 Jan 28, 2026
5ee9fbd
set guided mission_item altitude mode
xznhj8129 Jan 28, 2026
1521edb
mode fixgit status!
xznhj8129 Feb 24, 2026
870d50b
add mavlink doc
xznhj8129 Feb 24, 2026
2ac7b28
qodo fixes + set_pos_tgt_global alt change + docs
xznhj8129 Mar 4, 2026
2a1b71f
fixed stream rate runaway on radio_status, realtime stream rate cap, …
xznhj8129 Mar 6, 2026
8d2084a
clean up msp alt decode
xznhj8129 Mar 6, 2026
da7e20e
fixed version + autocontinue
xznhj8129 Mar 6, 2026
0a23646
fixed unit test
xznhj8129 Mar 29, 2026
83d35ee
Regenerate MSP docs for mav_fix2 rebase
xznhj8129 May 20, 2026
4bc5419
Remove accidental empty dm file
xznhj8129 May 20, 2026
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
131 changes: 131 additions & 0 deletions docs/Mavlink.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,131 @@
# 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**: only a subset of commands is implemented; unsupported commands are `COMMAND_ACK`ed as `UNSUPPORTED`.
- **Mission handling**: uploads are rejected while armed (except legacy guided waypoint writes). Mission frames are validated per command and unsupported frames are rejected.
- **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); most inbound handlers only act on packets targeted to this system ID.
- `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`: 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).
- `EXTENDED_SYS_STATE`: publishes landed state.
- `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).
- On-demand (command-triggered) messages: `AUTOPILOT_VERSION`, `PROTOCOL_VERSION`, `MESSAGE_INTERVAL`, `HOME_POSITION`, `AVAILABLE_MODES`, and `CURRENT_MODE`.

## 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` / `MISSION_ITEM_INT`: stores mission waypoints; rejects unsupported frames/sequence errors. Upload while armed is rejected except legacy guided waypoint writes.
- `MISSION_REQUEST_LIST`, `MISSION_REQUEST`, `MISSION_REQUEST_INT`: downloads active mission items; returns `MISSION_ACK` on bad sequence.
- `MISSION_CLEAR_ALL`: clears stored mission.
- `COMMAND_LONG` / `COMMAND_INT`: command transport for supported `MAV_CMD_*` handlers.
- `REQUEST_DATA_STREAM`: legacy stream-rate control per stream group. `MAV_DATA_STREAM_ALL` (0) applies to all INAV-scheduled groups (`EXTENDED_STATUS`, `RC_CHANNELS`, `POSITION`, `EXTRA1`, `EXTRA2`, `EXTRA3`, `EXTENDED_SYS_STATE`); `start_stop==0` stops the addressed stream(s).
- `SET_POSITION_TARGET_GLOBAL_INT`: requires matching `target_system` and `target_component` (`0` or local component), validates frame/type-mask semantics, updates guided WP255 for XY targets, and supports altitude-only control (`X/Y ignore`, `Z set`) using the same datum logic as `MAV_CMD_DO_CHANGE_ALTITUDE`.
- `RC_CHANNELS_OVERRIDE` passes channel values to the MAVLink serial receiver backend when targeted to the local system ID.
- `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.

- `MAV_CMD_DO_REPOSITION`: sets the Follow Me/GCS Nav waypoint when GCS NAV is valid. Accepts `MAV_FRAME_GLOBAL`, `MAV_FRAME_GLOBAL_INT`, `MAV_FRAME_GLOBAL_RELATIVE_ALT`, `MAV_FRAME_GLOBAL_RELATIVE_ALT_INT`; otherwise `UNSUPPORTED`.
- `MAV_CMD_DO_CHANGE_ALTITUDE`: supported when barometer support is compiled (`USE_BARO`); accepts global/global-int (MSL datum) and global-relative/global-relative-int (takeoff-relative datum), then calls navigation altitude-target update.
- `MAV_CMD_SET_MESSAGE_INTERVAL` / `MAV_CMD_GET_MESSAGE_INTERVAL`: adjust or query telemetry stream output for supported message IDs (streamed messages only; intervals slower than 1 Hz are not accepted).
- `MAV_CMD_GET_HOME_POSITION`: replies with `HOME_POSITION` when home fix exists.
- `MAV_CMD_REQUEST_MESSAGE`: emits one selected message (`HEARTBEAT`, `SYS_STATUS`, `ATTITUDE`, `VFR_HUD`, `AVAILABLE_MODES`, `CURRENT_MODE`, `EXTENDED_SYS_STATE`, RC channels, GPS/global/origin, battery/pressure, and `HOME_POSITION` when available) or `UNSUPPORTED`.
- `MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES`: returns stub `AUTOPILOT_VERSION` (v2 only; v1 returns `UNSUPPORTED`).
- `MAV_CMD_REQUEST_PROTOCOL_VERSION`: returns stub `PROTOCOL_VERSION` (v2 only; v1 returns `UNSUPPORTED`).

## Mode mappings (INAV → MAVLink/ArduPilot)

`custom_mode` is derived from active INAV telemetry flight mode (`getFlightModeForTelemetry()`), then mapped per vehicle type.

- **Multirotor profiles**
- ACRO / ACRO AIR → **ACRO**
- ANGLE / HORIZON / ANGLE HOLD → **STABILIZE**
- ALT HOLD → **ALT_HOLD**
- POS HOLD → **GUIDED** (if GCS valid), otherwise **POSHOLD**
- RTH → **RTL**
- MISSION → **AUTO**
- LAUNCH → **THROW**
- FAILSAFE → **RTL** (RTH/other phases) or **LAND** (landing phase)
- Any other unmapped mode falls back to **STABILIZE**
- **Fixed-wing profiles**
- MANUAL → **MANUAL**
- ACRO / ACRO AIR → **ACRO**
- ANGLE → **FBWA**
- HORIZON / ANGLE HOLD → **STABILIZE**
- ALT HOLD → **FBWB**
- POS HOLD → **GUIDED** (if GCS valid), otherwise **LOITER**
- RTH → **RTL**
- MISSION → **AUTO**
- CRUISE → **CRUISE**
- LAUNCH → **TAKEOFF**
- FAILSAFE → **RTL** (RTH/other phases) or **AUTOLAND** (landing phase)
- Any other unmapped mode falls back to **MANUAL**

## 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` (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 |
| `EXT_SYS_STATE` | `EXTENDED_SYS_STATE` | 1 Hz (defaults to `mavlink_extra3_rate`) |
| `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.


## MAVLink Missions

Partial compatibility with MAVLink mission planners such as QGC is implemented, however the differences between the two protocols means INAV cannot be programmed to it's full potential using only the MAVLINK mission protocol; only simple missions are possible. It is recommended to use MultiWii Planner or the INAV Configurator to program missions.

## MSP mission parity gaps (MAV ↔ MSP)

- WAYPOINT: MSP→MAV sends lat/lon/alt but drops leg speed `p1` and all user-action bits in `p3` (only alt-mode bit drives frame). MAV→MSP stores lat/lon/alt but forces `p1=0`, `p2=0`, keeps only alt-mode bit in `p3`; leg speed and user bits are lost.
- POSHOLD_TIME / LOITER_TIME: loiter time `p1` OK; leg speed `p2` and user-action bits in `p3` are discarded both directions.
- LAND: lat/lon/alt OK; leg speed `p1`, ground elevation `p2`, and user-action bits in `p3` are cleared in both directions (only alt-mode bit is retained from frame on upload).
- RTH: RTH land-if-nonzero flag in `p1` is ignored both ways (always zeroed); user-action bits dropped; alt is sent only if the MAVLink frame is coordinate and returns with alt-mode bit set on upload.
- JUMP: target and repeat count OK
- SET_POI: lat/lon/alt OK; `param1` is fixed to `MAV_ROI_LOCATION`; user-action bits in `p3` are dropped (alt-mode bit respected on upload).
- SET_HEAD: heading `p1` OK; user-action bits in `p3` are not represented.
- Net effect: actions and positions OK, but MSP-specific fields (leg speed, LAND elevation adjustment, RTH land flag, user-action bits in `p3`) are lost, so MAVLink missions cannot fully conform to `MSP_navigation_messages.md`.
16 changes: 15 additions & 1 deletion docs/development/msp/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -450,6 +450,7 @@ When the MSP JSON specification changes, bump `msp_messages.json` version:
[8736 - MSP2_INAV_FULL_LOCAL_POSE](#msp2_inav_full_local_pose)
[8737 - MSP2_INAV_SET_WP_INDEX](#msp2_inav_set_wp_index)
[8739 - MSP2_INAV_SET_CRUISE_HEADING](#msp2_inav_set_cruise_heading)
[8752 - MSP2_INAV_SET_AUX_RC](#msp2_inav_set_aux_rc)
[12288 - MSP2_BETAFLIGHT_BIND](#msp2_betaflight_bind)
[12289 - MSP2_RX_BIND](#msp2_rx_bind)

Expand Down Expand Up @@ -2311,7 +2312,7 @@ When the MSP JSON specification changes, bump `msp_messages.json` version:
| `hdop` | `uint16_t` | 2 | HDOP * 100 | Horizontal Dilution of Precision (`gpsSol.hdop`) |
| `eph` | `uint16_t` | 2 | cm | Estimated Horizontal Position Accuracy (`gpsSol.eph`) |
| `epv` | `uint16_t` | 2 | cm | Estimated Vertical Position Accuracy (`gpsSol.epv`) |
| `hwVersion` | `uint32_t` | 4 | Version code | GPS hardware version (`gpsState.hwVersion`). Values: 500=UBLOX5, 600=UBLOX6, 700=UBLOX7, 800=UBLOX8, 900=UBLOX9, 1000=UBLOX10, 0=UNKNOWN |
| `hwVersion` | `uint8_t` | 1 | - | GPS hardware version bit-field: bits[7:6]=series (0b01=u-blox Neo/M), bits[5:0]=generation. E.g. 0x48=M8, 0x49=M9, 0x4A=M10, 0=unknown. |

**Notes:** Requires `USE_GPS`.

Expand Down Expand Up @@ -4710,6 +4711,19 @@ When the MSP JSON specification changes, bump `msp_messages.json` version:

**Notes:** Returns error if the aircraft is not armed or `NAV_COURSE_HOLD_MODE` is not active. On success, sets both `posControl.cruise.course` and `posControl.cruise.previousCourse` to the normalised value, preventing spurious heading adjustments from `getCruiseHeadingAdjustment()` on the next control cycle.

## <a id="msp2_inav_set_aux_rc"></a>`MSP2_INAV_SET_AUX_RC (8752 / 0x2230)`
**Description:** Bandwidth-efficient auxiliary RC channel update. Sets CH13-CH32 with configurable resolution (2/4/8/16-bit) without affecting primary flight controls. Designed for extending channel count beyond native RC link capacity via MSP passthrough.

**Request Payload:**
|Field|C Type|Size (Bytes)|Units|Description|
|---|---|---|---|---|
| `definitionByte` | `uint8_t` | 1 | - | Packed start channel and resolution. Bits 7-3: start channel index (valid range 12-31 for CH13-CH32; 0-11 rejected as error). Bits 2-0: resolution mode (0=2-bit, 1=4-bit, 2=8-bit, 3=16-bit; 4-7 reserved/error). |
| `channelData` | `uint8_t[]` | array | PWM (encoded) | Packed channel values, sequential from start channel. Number of channels is derived from data size and resolution. Value 0 means skip (no update). Sub-byte modes (2-bit, 4-bit) are packed MSB-first. 2-bit values 1-3 map to 1000/1500/2000us. 4-bit values 1-15 map to 1000 + (val-1)*1000/14 us. 8-bit values 1-255 map to 1000 + (val-1)*1000/254 us. 16-bit values are direct PWM, clamped to 750-2250us. |

**Reply Payload:** **None**

**Notes:** CH1-CH12 (index 0-11) are protected and will return `MSP_RESULT_ERROR`. Payload size must be 2-49 bytes. Constraint: `startChannel + channelCount <= 32`. Values persist until overwritten; no timeout. Applied as a post-RX overlay in `calculateRxChannelsAndUpdateFailsafe()` after MSP RC Override but before failsafe. Does not require `USE_RX_MSP` or MSP-RC-OVERRIDE flight mode. Does not affect failsafe detection. When MSP is the primary RX provider, channels covered by `MSP_SET_RAW_RC` are automatically skipped. Channels in the `mspOverrideChannels` bitmask are skipped when MSP RC Override mode is active. Recommended to send with `MSP_FLAG_DONT_REPLY` (flags=0x01) to save bandwidth on telemetry passthrough links. 16-bit mode requires even number of data bytes and values are clamped to 750-2250us.

## <a id="msp2_betaflight_bind"></a>`MSP2_BETAFLIGHT_BIND (12288 / 0x3000)`
**Description:** Initiates the receiver binding procedure for supported serial protocols (CRSF, SRXL2).

Expand Down
Loading
Loading