Skip to content

INAV Remote Management, Control and Telemetry

Jonathan Hudson edited this page Sep 4, 2022 · 26 revisions

INAV Remote Management, Control and Telemetry

Introduction

This article discusses INAV's APIs for remote control and telemetry. It does not discuss internal programming APIs (e.g. "how to interface a new sensor directly on the FC"), nor does it discuss the programmable logic conditions.

This article does not discuss radio control protocols, unless they also provide facilities for management or telemetry.

Note also that INAV's primary remote API is MultiWii Serial Protocol and this is the main object of discussion. Other protocols are also available and are also discussed.

Definitions

For the purpose of this article, the following definitions are used:

  • Remote Management: Methods to get and set internal parameters and data from and to the flight controller. This may be considered to be a super-set of the information that can be shown / updated from the INAV Configurator. It should be noted that setting / using much of this information requires saving to EEPROM and thus cannot (safely) be used when the vehicle is armed.

  • Remote Control: Methods to alter the behaviour of the vehicle when armed. This includes overriding or replacing the radio TX "stick commands" and "follow me" functionality.

  • Telemetry: Methods to receive status and geospatial data from the vehicle. This is typically sent unsolicited (e.g. once telemetry is configured it will be sent without further action from the receiver / consumer).

All of the above are message based, requiring a communications channel, which may be considered to be a combination of:

  • A hardware device. Usually a serial UART on the FC, and another device on the consumer, whose end point may also be a serial device, or be encapsulated in some other form, for example a WiFi access point or Bluetooth.

  • A physical transport. This could be a cable (USB, 4 wire serial) or a radio link (either a RC radio or a dedicated radio link using technologies such as LoRa, HC-12 or "3DR / SiK").

  • A protocol. The protocol defines how the data is serialised for transmission over the physical transport; examples discussed include MSP and LTM.

Note that as far as the INAV firmware is concerned, we are discussing "serial" transmission / reception regardless of the physical transport between the vehicle and consumer.

Use cases

The following use cases are pertinent to the technologies and techniques discussed below:

  • Configuration of the flight controller
  • A Mission Planner
  • Ground station
  • Co-processor on the vehicle for applications such as obstacle avoidance

INAV Considerations, Restrictions and Recommendations

INAV places a number of restrictions on the number of channels available and their usage:

  • There can be up to three MSP channels
  • A MSP channel can be shared with a telemetry channel such that the channel is available for MSP (request-response, solicited) communications when unarmed and the unsolicited telemetry when armed. The most common use case for this is MSP (unarmed) and LTM or MAVLink (armed). The consumer has to be able to handle the transition (the arming MSP -> LTM / MAVLink transition is easy, the consumer can recognise the protocol has changed, the disarm LTM / MAVLink -> MSP transition can only be handled via a timeout in message reception).
  • There can be multiple telemetry protocols active at the same time (on different channels).
  • In particular, MSP is a request-response protocol.
    • Do NOT spam the FC with a rapid, timer based stream of messages; the FC has limited buffering and processing capability and messages may be lost.
    • Check MSP responses, both the message ID is that expected and the response code indicates the message was correctly processed by the FC (see below).
    • Implement a timeout mechanism to deal with lost messages and retry.
    • Set the MSP payload length correctly, it is validated by the FC (5.0 and later).
  • Verify the checksum available in all the protocols. Discard corrupt messages

Protocols

High level overview

Remote Management

MSP (MultiWii Serial Protocol) is only protocol that provides for remote management and provides comprehensive coverage of the facilities and functions of INAV. MSP is (largely) a request / response protocol; typically the consumer requests data from the FC, which the FC provides. There are a small number of specialised cases where MSP is provided unsolicited (for example INAV radar).

Remote Control

MSP (MultiWii Serial Protocol) and MAVLink can be used for remote control.

Telemetry

LTM (Lightweight Telemetry), MAVLink and various RC radio protocols (e.g. Smartport, Crossfire (CRSF), FlySky provide essentially unsolicited telemetry.

MultiiWii Serial Protocol

Multiwii Serial Protocol originated on the MultiWii Flight controller around 2010. The original documention is available in the Multiwii wiki; the details should not be relied upon for INAV / Betaflight implementations (or even 2.4 MultiWii).

INAV supports the following variations:

  • MSPv1: This is considered obsolescent; it is limited to a 255 byte payload, 255 message IDs (commands) and has a weak checksum. It is not recommended from new implementations; as far as INAV is concerned it is deprecated and likely to be removed from a future release.
  • MSPv1 + Jumbo frames: An extension to MSPv1 to support frames larger than 255 bytes.
  • MSPV2: Recommended version. Addresses the weakness of prior versions, 16bit message ID, 16bit payload length and stronger CRC.

MSP References

INAV Wiki MSPV2 definition.

INAV Wiki MSP Navigation Messages. Detailed explanation of the usage of INAV / MSP Way point definitions.

For INAV the normative reference for MSP is the source code:

There are numerous open source implementations (libraries and application modules); in addition to the INAV FC source:

  • INAV Configurator
  • Numerous libraries for various platforms (Arduino, generic computer) in numerous languages (e.g. C, C++, Python, Rust). Google is your friend here.
  • Application implementations (mwptools, BulletGCSS, Mobile Flight). Again, Google is your friend here.

There is also a long abandoned (alas) changelog of historic interest only.

Note that the INAV developers take backwards compatibility seriously; changing a payload is usually not permitted (however, extending it is OK); this is why there are a number of variations on the same basic request (MSP_STATUS, MSP_STATUS_EX, MSP2_INAV_STATUS) as the size of the internal status structure has changed.

MAVLink

Lightweight Telemetry

LTM offers low data rate / low band width / high update rate telemetry. Since its introduction to INAV, a number of extension have been added; these, and the original frames, are documented in the wiki, in detail.

INAV compatible LTM is implemented by Ghettostation, LTM Telemetry OLED , EZGUI and mwptools at least.

RC Protocols

Note:

  • This section describes the telemetry aspects only. If you wish to investigate the control aspects, see the INAV protocol specific source files.
  • There are various implementations / initiatives to provide MSP over an RC Link. This topic is currently beyond the scope of this article.
  • Typically this data is sent over the RC Control (TX/RX) radio link. Radio specific hardware / transport may be required (serial inverter, Bluetooth, WiFi etc.) may be required to access the data.

Smartport

Crossfire

  • INAV source code. Telemetry
  • Other Example. mwptools example. Protocol description, example parser, links to other information sources.

Flysky / IBUS

  • INAV source code. Telemetry.
  • Other Example. mwptools example. This example uses the OpenTX/EdgeTX MPM (Multi-Protocol Module) to access IBUS / Flysky AA telemetry data and provides a link to the original MPM definition and requires the INAV CLI setting set ibus_telemetry_type = 0

Specific Use Cases

(work in progress)

Remote Control using MSP / MAVLink

The MSP messages MSP_SET_RAW_RC / MSP_RC can be used to implement remote control via MSP (i.e. 16 channel control, stick commands).

There is an sample application that describes the requirements / restrictions / idiosyncrasies involved using the MSP interface.

Likewise, the MAVLink RC_CHANNELS_OVERRIDE, RC_CHANNELS_OVERRIDE_RAW, RC_CHANNELS. See, inter alia, INAV #8282 and INAV #8132 and INAV #8173 for limitation / caveats / current implementation status.

Follow Me (NAV GCS).

INAV has provided a "follow me" implementation via MSP since v1.2/1.3 (2016). This allows the user to direct the vehicle to fly to a specific location. This was intended for mobile ground station (specifically the obsolete Android application "EZGUI") to instruct the vehicle to follow a GPS equipped target (often the pilot).

  • The FC is placed in POSHOLD and NAV GCS modes.
  • The consumer updates WP#255 (holds the requested POSHOLD location) using MSP_SET_WP messages.
  • See INAV source.

The "Obstacle Avoidance" problem

Ever so often, someone asks on Discord / Telegram / chat platform du jour how to do "Obstacle Avoidance" on INAV, often with some assumptions that:

  • There is a relatively powerful (compared to the FC) co-processor (Rpi, Jetson Nano) with sensors and the CPU power to detect / classify obstacles from its on board sensors.
  • The range, azimuth and elevation (at least relative to the vehicle) of the obstacle is known via the co-processor / sensors.

If would seem that there are at least two options using the remote control / management (MSP) API.

Use remote control to pilot the vehicle

The vehicle is commanded via Remote Control (MSP or MAVLink) to fly around the obstacle by providing inputs to the Roll, Pitch, Yaw and Throttle channels. The co-processor would compute the channel values required to manoeuvre the vehicle, based on some internal model of the vehicle physics. This seems to be a complex approach, particularly the computation of channel values required, which have to be continually updated (5Hz for MSP).

The vehicle's navigation engine is used

  • The obstacle's location in known from the sensors with reference to the vehicle (range, azimuth, elevation).
  • The vehicle's location is known in geospatial coordinates (latitude, longitude, altitude) as well as the speed and heading, (MSP_RAW_GPS, MSP_ATTITUDE etc.).
  • A safe location can be calculated based on the vehicle's location and the relative location of the obstacle.
  • The vehicle can be commanded using MSP_SET_WP for WP #255 to use its navigation system to avoid the obstacle (with POSHOLD and NAV GCS modes activated).

Potentially a less complex solution, as the piloting of the vehicle is done by the well proven flight controller firmware.

Other References

WIKI TOPICS

Wiki Home Page

INAV Version Release Notes

7.1.0 Release Notes
7.0.0 Release Notes
6.0.0 Release Notes
5.1 Release notes
5.0.0 Release Notes
4.1.0 Release Notes
4.0.0 Release Notes
3.0.0 Release Notes
2.6.0 Release Notes
2.5.1 Release notes
2.5.0 Release Notes
2.4.0 Release Notes
2.3.0 Release Notes
2.2.1 Release Notes
2.2.0 Release Notes
2.1.0 Release Notes
2.0.0 Release Notes
1.9.1 Release notes
1.9.0 Release notes
1.8.0 Release notes
1.7.3 Release notes
Older Release Notes

QUICK START GUIDES

Getting started with iNav
Fixed Wing Guide
Howto: CC3D flight controller, minimOSD , telemetry and GPS for fixed wing
Howto: CC3D flight controller, minimOSD, GPS and LTM telemetry for fixed wing
INAV for BetaFlight users
launch mode
Multirotor guide
YouTube video guides
DevDocs Getting Started.md
DevDocs INAV_Fixed_Wing_Setup_Guide.pdf
DevDocs Safety.md

Connecting to INAV

Bluetooth setup to configure your flight controller
DevDocs Wireless Connections (BLE, TCP and UDP).md\

Flashing and Upgrading

Boards, Targets and PWM allocations
Upgrading from an older version of INAV to the current version
DevDocs Installation.md
DevDocs USB Flashing.md

Setup Tab
Live 3D Graphic & Pre-Arming Checks

Calibration Tab
Accelerometer, Compass, & Optic Flow Calibration

Alignment Tool Tab
Adjust mount angle of FC & Compass

Ports Tab
Map Devices to UART Serial Ports

Receiver Tab
Set protocol and channel mapping

Mixer

Mixer Tab
Custom mixes for exotic setups
DevDocs Mixer.md

Outputs

DevDocs ESC and servo outputs.md
DevDocs Servo.md

Modes

Modes
Navigation modes
Navigation Mode: Return to Home
DevDocs Controls.md
DevDocs INAV_Modes.pdf
DevDocs Navigation.md

Configuration

Sensor auto detect and hardware failure detection

Failsafe

Failsafe
DevDocs Failsafe.md

PID Tuning

PID Attenuation and scaling
Fixed Wing Tuning for INAV 3.0
Tune INAV PIFF controller for fixedwing
DevDocs Autotune - fixedwing.md
DevDocs INAV PID Controller.md
DevDocs INAV_Wing_Tuning_Masterclass.pdf
DevDocs PID tuning.md
DevDocs Profiles.md

GPS

GPS and Compass setup
GPS Failsafe and Glitch Protection

OSD and VTx

DevDocs Betaflight 4.3 compatible OSD.md
OSD custom messages
OSD Hud and ESP32 radars
DevDocs OSD.md
DevDocs VTx.md

LED Strip

DevDocs LedStrip.md

ADVANCED

Advanced Tuning

Fixed Wing Autolaunch
DevDocs INAV_Autolaunch.pdf

Programming

DevDocs Programming Framework.md

Adjustments

DevDocs Inflight Adjustments.md

Mission Control

iNavFlight Missions
DevDocs Safehomes.md

Tethered Logging

Log when FC is connected via USB

Blackbox

DevDocs Blackbox.md
INAV blackbox variables
DevDocs USB_Mass_Storage_(MSC)_mode.md

CLI

iNav CLI variables
DevDocs Cli.md
DevDocs Settings.md

VTOL

DevDocs MixerProfile.md
DevDocs VTOL.md

TROUBLESHOOTING

"Something" is disabled Reasons
Blinkenlights
Pixel OSD FAQs
TROUBLESHOOTING
Why do I have limited servo throw in my airplane

ADTL TOPICS, FEATURES, DEV INFO

AAT Automatic Antenna Tracker
Building custom firmware
Default values for different type of aircrafts
Features safe to add and remove to fit your needs.
Developer info
INAV MSP frames changelog
INAV Remote Management, Control and Telemetry
Lightweight Telemetry (LTM)
Making a new Virtualbox to make your own INAV
MSP Navigation Messages
MSP V2
OrangeRX LRS RX and OMNIBUS F4
Rate Dynamics
Target and Sensor support
UAV Interconnect Bus
Ublox 3.01 firmware and Galileo
DevDocs 1wire.md
DevDocs ADSB.md
DevDocs Battery.md
DevDocs Buzzer.md
DevDocs Channel forwarding.md
DevDocs Display.md
DevDocs Fixed Wing Landing.md
DevDocs GPS_fix_estimation.md
DevDocs LED pin PWM.md
DevDocs Lights.md
DevDocs OSD Joystick.md
DevDocs Servo Gimbal.md
DevDocs Temperature sensors.md

OLD LEGACY INFO

Supported boards
DevDocs Boards.md
Legacy Mixers
Legacy target ChebuzzF3
Legacy target Colibri RACE
Legacy target Motolab
Legacy target Omnibus F3
Legacy target Paris Air Hero 32
Legacy target Paris Air Hero 32 F3
Legacy target Sparky
Legacy target SPRacingF3
Legacy target SPRacingF3EVO
Legacy target SPRacingF3EVO_1SS
DevDocs Configuration.md
Request form new PRESET
DevDocs Introduction.md
Welcome to INAV, useful links and products
iNav Telemetry
DevDocs Rangefinder.md
DevDocs Rssi.md
DevDocs Runcam device.md
DevDocs Serial.md
DevDocs Telemetry.md
DevDocs Rx.md
DevDocs Spektrum bind.md

Clone this wiki locally