replace INAV code line reference to function reference
[inav.wiki.git] / INAV-Remote-Management,-Control-and-Telemetry.md
blob2782cb512db4374951b6d5a21214a12297aea3c4
1 # INAV Remote Management, Control and Telemetry
3 ## Introduction
5 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](https://github.com/iNavFlight/inav/blob/master/docs/Programming%20Framework.md).
7 This article does not discuss radio control protocols, unless they also provide facilities for management or telemetry.
9 Note also that INAV's primary remote API is [MultiWii Serial Protocol](#multiwii-serial-protocol) and this is the main object of discussion. Other protocols are also available and are also discussed.
11 ## Definitions
13 For the purpose of this article, the following definitions are used:
15 * **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](https://github.com/iNavFlight/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.
17 * **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.
19 * **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).
21 All of the above are message based, requiring a **communications channel**, which may be considered to be a combination of:
23 * 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.
25 * 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").
27 * A protocol. The protocol defines how the data is serialised for transmission over the physical transport; examples discussed include [MSP](#multiwii-serial-protocol) and [LTM](#lightweight-telemetry).
29 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.
31 ## Use cases
33 The following use cases are pertinent to the technologies and techniques discussed below:
35 * Configuration of the flight controller
36 * A Mission Planner
37 * Ground station
38 * Co-processor on the vehicle for applications such as obstacle avoidance
40 ## INAV Considerations, Restrictions and Recommendations
42 INAV places a number of restrictions on the number of channels available and their usage:
44 * There can be up to three MSP channels
45 * 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).
46 * There can be multiple telemetry protocols active at the same time (on different channels).
47 * In particular, MSP is a request-response protocol.
48   - 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.
49   - 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](#multiwii-serial-protocol)).
50   - Implement a timeout mechanism to deal with lost messages and retry.
51   - Set the MSP payload length correctly, it is validated by the FC (5.0 and later).
52 * Verify the checksum available in all the protocols. Discard corrupt messages
54 ## Protocols
56 ### High level overview
58 #### Remote Management
60 [MSP (MultiWii Serial Protocol)](#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).
62 #### Remote Control
64 [MSP (MultiWii Serial Protocol)](#multiwii-serial-protocol) and [MAVLink](#mavlink) can be used for remote control.
66 #### Telemetry
68 [LTM (Lightweight Telemetry)](#lightweight-telemetry), [MAVLink](#mavlink) and various RC radio protocols (e.g. [Smartport](#smartport), [Crossfire (CRSF)](#crossfire), [FlySky](#flysky) provide essentially unsolicited telemetry.
70 ### MultiWii Serial Protocol
72 Multiwii Serial Protocol originated on the MultiWii Flight controller around 2010. The original documention is available in the [Multiwii wiki](http://www.multiwii.com/wiki/index.php?title=Multiwii_Serial_Protocol); the details should not be relied upon for INAV / Betaflight implementations (or even 2.4 MultiWii).
74 INAV supports the following variations:
76 * 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.
77 * MSPv1 + Jumbo frames: An extension to MSPv1 to support frames larger than 255 bytes.
78 * MSPV2: Recommended version. Addresses the weakness of prior versions, 16bit message ID, 16bit payload length and stronger CRC.
80 #### MSP References
82 [INAV Wiki MSPV2 definition](https://github.com/iNavFlight/inav/wiki/MSP-V2).
84 [INAV Wiki MSP Navigation Messages](https://github.com/iNavFlight/inav/wiki/MSP-Navigation-Messages). Detailed explanation of the usage of INAV / MSP Way point definitions.
86 For INAV the normative reference for MSP is the source code:
88 * [Message IDs](https://github.com/iNavFlight/inav/tree/master/src/main/msp)
89 * [Message Handling](https://github.com/iNavFlight/inav/blob/master/src/main/fc/fc_msp.c) and related source files (`fc_msp*.*`) in the same directory for specific detail.
90 * [RC Control](https://github.com/iNavFlight/inav/blob/master/src/main/rx/msp.c) and related `*msp*.*` files in the same directory.
92 There are numerous open source implementations (libraries and application modules); in addition to the INAV FC source:
94 * INAV Configurator
95 * Numerous libraries for various platforms (Arduino, generic computer) in numerous languages (e.g. C, C++, Python, Rust). Google is your friend here.
96 * Application implementations (mwptools, BulletGCSS, Mobile Flight). Again, Google is your friend here.
98 There is also a long abandoned (alas) [changelog](https://github.com/iNavFlight/inav/wiki/INAV-MSP-frames-changelog) of historic interest only.
100 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.
102 ### MAVLink
104 * [MAVlink developer info](https://mavlink.io/en/). Note that INAV supports a small subset of the MAVLink message set (some unsolicited telemetry and remote control). INAV supports MAVLink V1 and V2.
105 * There is a application in the [mwptools repository, mavtest](https://github.com/stronnag/mwptools/tree/master/src/samples/mavtest) that summarises / validates the MAVLink messages supported by INAV.
106 * INAV source code.
107   - [Telemetry](https://github.com/iNavFlight/inav/blob/master/src/main/telemetry/mavlink.c)
108   - [RC Control](https://github.com/iNavFlight/inav/blob/master/src/main/rx/mavlink.c)
110 ### Lightweight Telemetry
112 LTM offers low data rate / low band width / high update rate telemetry.
113 Since its introduction to INAV, a number of extension have been added; these, and the original frames, are [documented in the wiki](https://github.com/iNavFlight/inav/wiki/Lightweight-Telemetry-(LTM)), in detail.
115 * INAV source code. [Telemetry](https://github.com/iNavFlight/inav/blob/master/src/main/telemetry/ltm.c).
117 INAV compatible LTM is implemented by [Ghettostation](https://github.com/KipK/Ghettostation), [LTM Telemetry OLED ](https://github.com/sppnk/LTM-Telemetry-OLED) , [EZGUI](http://ez-gui.com/) and [mwptools](https://github.com/stronnag/mwptools) at least.
119 ### RC Protocols
121 Note:
123 * This section describes the telemetry aspects only. If you wish to investigate the control aspects, see the INAV [protocol specific source files](https://github.com/iNavFlight/inav/blob/master/src/main/rx/).
124 * There are various implementations / initiatives to provide MSP over an RC Link. This topic is currently beyond the scope of this article.
125 * 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.
127 #### Smartport
129 * INAV source code. [Telemetry](https://github.com/iNavFlight/inav/blob/master/src/main/telemetry/smartport.c).
130 * Other Example. Parser / decoder / replay tools. [mwptools example](https://github.com/stronnag/mwptools/tree/master/src/samples/frsky).
132 #### Crossfire
134 * INAV source code. [Telemetry](https://github.com/iNavFlight/inav/blob/master/src/main/telemetry/crsf.c)
135 * Other Example. [mwptools example](https://github.com/stronnag/mwptools/tree/master/src/samples/crsf). Protocol description, example parser, links to other information sources.
137 #### Flysky / IBUS
139 * INAV source code. [Telemetry](https://github.com/iNavFlight/inav/blob/master/src/main/telemetry/ibus.c).
140 * Other Example. [mwptools example](https://github.com/stronnag/mwptools/tree/master/src/samples/mpm-telemetry). 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`
142 ## Specific Use Cases
144 (**work in progress**)
146 ### Remote Control using MSP / MAVLink
148 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).
150 There is a [sample application](https://github.com/stronnag/msp_set_rx) that describes the requirements / restrictions / idiosyncrasies involved using the MSP interface.
152 Likewise, the MAVLink `RC_CHANNELS_OVERRIDE`, `RC_CHANNELS_OVERRIDE_RAW`, `RC_CHANNELS`. See, inter alia,  [INAV #8282](https://github.com/iNavFlight/inav/pull/8282) and [INAV #8132](https://github.com/iNavFlight/inav/issues/8132) and [INAV #8173](https://github.com/iNavFlight/inav/pull/8273) for limitation / caveats / current implementation status.
154 ### Follow Me (`GCS NAV`).
156 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). [mwp](https://github.com/stronnag/mwptools) supports `GCS NAV`, allowing in flight selection of a "follow me" point on the map, which is then transmitted to the vehicle.
158 * The FC is placed in `POSHOLD` and `GCS NAV` modes.
159 * The consumer updates 'special' `WP#255` (holds the requested `POSHOLD` location) using `MSP_SET_WP` messages.
160 * See [INAV source](https://github.com/iNavFlight/inav/blob/master/src/main/navigation/navigation.c), `setWaypoint()` function.
162 With `GCS NAV`, is also possible to update the home position via WP#0
164 #### Querying locations
166 The following 'special' WPs can be interrogated with the `MSP_WP` message:
168 * `WP#0` returns the home position
169 * `WP#254` returns the desired position, i.e. that set by `MSP_SET_WP` / `WP#255`
170 * `WP#255` returns the current position.
172 ### The "Obstacle Avoidance" problem
174 Ever so often, someone asks on Discord / Telegram / chat platform du jour how to do "Obstacle Avoidance" on INAV, often with some assumptions that:
176 * 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.
177 * The range, azimuth and elevation (at least relative to the vehicle) of the obstacle is known via the co-processor / sensors.
179 If would seem that there are at least two options using the remote control / management (MSP) API.
181 #### Use remote control to pilot the vehicle
183 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).
185 #### The vehicle's navigation engine is used
187 * The obstacle's location in known from the sensors with reference to the vehicle (range, azimuth, elevation).
188 * 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.).
189 * A safe location can be calculated based on the vehicle's location and the relative location of the obstacle.
190 * 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).
192 Potentially a less complex solution, as the piloting of the vehicle is done by the well proven flight controller firmware.
194 ## Further Considerations
196 ### Partial Automation
198 It is possible to combine manual control with some channel automation.
200 * Compile the firmware with `USE_MSP_RC_OVERRIDE` defined (e.g. in `src/main/target/common.h`).
201 * Use the CLI `msp_override_channels` to define the channels to be automated.
202 * Ensure the channel(s) are refreshed at a minimum of 5Hz to avoid fail-safe.
204 ### Control by stick commands
206 In a cruise mode (e.g. POSHOLD/CRUISE for multi-rotor), it will be possible to fly the craft using A,E,R stick emulation, with minimal concern for flight physics.
208 ### Useful / relevant MSP stanzas and application
210 The following `MSP` stanzas may be useful for remote control / automation applications.
212 #### Pre-flight setup
214 Prior to arming the craft, an automation application can be made "target agnostic" by requesting data from the FC. A specific application may need some or all of:
216 * `MSP_FC_VARIANT` : Validate that you're running on INAV.
217 * `MSP_API_VERSION`, `MSP_FC_VERSION` : Validate that the firmware is sufficiently capable for your application.
218 * `MSP_RX_MAP` : Obtain channel map for subsequent `MSP_SET_RAW_RC`.
219 * `MSP2_COMMON_SETTING` / `nav_extra_arming_safety` : Checking arming requirement and whether you can bypass it
220 * `MSP_MODE_RANGES`: Determine the configured switches, functions and ranges.
221 * `MSP_BOXNAMES` : Determine the modes available to the craft (e.g. for mode validation via `MSP2_INAV_STATUS`).
222 * `MSP2_COMMON_SERIAL_CONFIG` : Determine serial channel functions.
223 * `MSP_RX_CONFIG` : Determine the RX type.
224 * `MSP2_INAV_STATUS` : Determining various status items (arming status, mode status etc.)
225 * `MSP2_INAV_MIXER` : Get vehicle type (e.g. to avoid MR only actions on FW).
227 #### Flight (and some pre-flight)
229 * `MSP_SET_RAW_RC` : Set RC channel values (PWM values), both for "stick" and "switch" channels.
230 * `MSP2_INAV_STATUS` : Determining various status items (arming status, mode status etc.)
231 * `MSP_RAW_GPS` : Get GPS data (fix, number of satellites, location)
232 * `MSP_SET_WP` : Set Waypoint (either for mission for "follow me").
233 * `MSP_WP` : Get Waypoint (e.g. to cache home location).
234 * `MSP2_INAV_ANALOG` : Battery status
235 * `MSP_ATTITUDE` : Vehicle attitude
236 * `MSP_ALTITUDE` : Vehicle altitude / vario
237 * `MSP_NAV_STATUS` : Navigation status
239 Note. These may not be comprehensive lists, but they are a start.
241 ### Notional Usage
243 The following may cover a number of "home work" / "undergraduate project" use cases:
245 #### Notional Requirement
247 Fully automated, using a co-processor for target detection and flight management
249 * Once powered on, the craft shall arm automatically.
250 * Once armed, the craft shall take off and loiter in a 'safe' location.
251 * The craft shall determine (by some 'magic' means, beyond the scope of this article), the 'target location')
252 * The craft shall fly to the target location (which may move as long as the vehicle is more than 50m from the target).
253 * Once the target is assumed stationary the vehicle shall land as close as possible to the target and disarm.
254 * If it unsafe to continue (e.g. low battery), the craft shall return to the launch location and land and disarm.
256 #### Notional Solution
258 Assumptions.
260 * Required modes are configured (`RTH`, `POSHOLD`, `GCS NAV`, `WP`).
261 * Configured for land / disarm on RTH.
262 * Co-processor / 'magic' sensor can determine target (relative) location.
264 Using the MSP outlined above:
266 * Determine vehicle characteristics. Stop now if not capable of mission.
267 * Monitor status and location until arming is possible (e.g. GPS fix).
268 * Using the 'magic' sensor / AI etc., determine a safe loiter location.
269 * Generate and upload a 1 WP mission to the safe location (the craft will automatically loiter there when completed). Ideally elevation will be double vertical range to avoid tip over on take off.
270 * Arm the craft, apply a little throttle, and immediately engage WP mode. The craft will take off and start the mission.
271 * Continually monitor location, battery and status.
272 * Once the craft reaches the loiter location, engage POSHOLD and disengage WP mode.
273 * Using the `magic` sensor, determine the target location. Assuming this is available as range and bearing (absolute or relative), calculate the geographic location of the target. Enable `GCS NAV` mode and update `WP#255` to fly the craft to the target.
274 * Repeat the above until target is determined to be the landing position (e.g. within 50m in the notional requirement).
275 * Cache launch position (i.e. read `WP#0`). Set the target position as `WP#0` (home), engage `RTH`.
276 * Craft will land at target location.
277 * If an unsafe condition is detected (low battery etc.), restore any cached home location and engage `RTH`.
279 Note: you could do most or all of the above just with `MSP_SET_RAW_RC` rather than with the navigation engine, but that might increase the co-processor computation / monitoring requirement and implementation risk.
281 #### Implementation example
283 NOTE: If you have a better example (or additional examples), please augment or replace the following paragraphs.
285 The [flightlog2kml](https://github.com/stronnag/bbl2kml) project contains a tool [fl2sitl](https://github.com/stronnag/bbl2kml/wiki/fl2sitl) that replays a blackbox log using the [INAV SITL](https://github.com/iNavFlight/inav/blob/master/docs/SITL/SITL.md). Specifically, this uses MSP and MSP_SET_RAW_RC to establish vehicle characteristics, monitor the vehicle status, arm the vehicle and set RC values for AETR and switches during log replay simulation to effectively "fly" the SITL for the recorded flight.
287 The MSP initialisation, MSP status monitoring and MSP RC management code is in [msp.go](https://github.com/stronnag/bbl2kml/blob/master/pkg/sitlgen/msp.go), specifically the `init()` and `run()` functions. Arming / disarming in [sitlgen.go](https://github.com/stronnag/bbl2kml/blob/master/pkg/sitlgen/sitlgen.go), `arm_action()` function.
289 ## Other References
291 * [Building custom INAV](https://github.com/iNavFlight/inav/wiki/Building-custom-firmware).
292 * [Developer Info / Navigation internals](https://github.com/iNavFlight/inav/wiki/Developer-info)