├── .pubignore ├── CHANGELOG.md ├── .gitmodules ├── lib ├── mavlink_version.dart ├── mavlink.dart ├── types.dart ├── mavlink_dialect.dart ├── crc.dart ├── mavlink_frame.dart ├── mavlink_message.dart ├── mavlink_parser.dart └── dialects │ ├── icarous.dart │ ├── csairlink.dart │ ├── minimal.dart │ └── standard.dart ├── test ├── mavlink_dialect │ ├── t00.xml │ ├── t01.xml │ ├── t02.xml │ ├── t04.xml │ └── t03.xml ├── mavlink_serialize_v1_test.dart ├── mavlink_parser_v2_test.dart ├── mavlink_parser_v1_test.dart └── generate_test.dart ├── pubspec.yaml ├── .gitignore ├── .github └── workflows │ └── dart.yml ├── example ├── parser.dart ├── parameter.dart └── sitl_test.dart ├── analysis_options.yaml ├── LICENSE ├── README.md └── tool └── generate.dart /.pubignore: -------------------------------------------------------------------------------- 1 | /mavlink -------------------------------------------------------------------------------- /CHANGELOG.md: -------------------------------------------------------------------------------- 1 | ## 0.1.0 2 | 3 | - Initial version. 4 | - Parse MAVLink v1 packets. 5 | -------------------------------------------------------------------------------- /.gitmodules: -------------------------------------------------------------------------------- 1 | [submodule "mavlink"] 2 | path = mavlink 3 | url = https://github.com/mavlink/mavlink.git 4 | -------------------------------------------------------------------------------- /lib/mavlink_version.dart: -------------------------------------------------------------------------------- 1 | library dart_mavlink; 2 | 3 | enum MavlinkVersion { 4 | v1, 5 | v2 6 | } 7 | -------------------------------------------------------------------------------- /test/mavlink_dialect/t00.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 0 4 | 0 5 | 6 | -------------------------------------------------------------------------------- /test/mavlink_dialect/t01.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | t00.xml 4 | 1 5 | 1 6 | 7 | -------------------------------------------------------------------------------- /lib/mavlink.dart: -------------------------------------------------------------------------------- 1 | library dart_mavlink; 2 | 3 | export 'mavlink_dialect.dart'; 4 | export 'mavlink_frame.dart'; 5 | export 'mavlink_message.dart'; 6 | export 'mavlink_parser.dart'; 7 | export 'mavlink_version.dart'; 8 | -------------------------------------------------------------------------------- /test/mavlink_dialect/t02.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 2 4 | 1 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | -------------------------------------------------------------------------------- /test/mavlink_dialect/t04.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 4 | 4 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | -------------------------------------------------------------------------------- /pubspec.yaml: -------------------------------------------------------------------------------- 1 | name: dart_mavlink 2 | description: MAVLink library for Dart. 3 | version: 0.1.0 4 | repository: https://github.com/nus/dart_mavlink 5 | environment: 6 | sdk: '>=2.13.0 <3.0.0' 7 | dev_dependencies: 8 | lints: ^1.0.0 9 | path: ^1.8.0 10 | test: ^1.17.12 11 | xml: ^5.3.1 12 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | # Files and directories created by pub. 2 | .dart_tool/ 3 | .packages 4 | 5 | # Conventional directory for build outputs. 6 | build/ 7 | 8 | # Omit committing pubspec.lock for library packages; see 9 | # https://dart.dev/guides/libraries/private-files#pubspeclock. 10 | pubspec.lock 11 | -------------------------------------------------------------------------------- /lib/types.dart: -------------------------------------------------------------------------------- 1 | library dart_mavlink; 2 | 3 | // ignore_for_file: camel_case_types 4 | 5 | typedef int8_t = int; 6 | typedef uint8_t = int; 7 | typedef int16_t = int; 8 | typedef uint16_t = int; 9 | typedef int32_t = int; 10 | typedef uint32_t = int; 11 | typedef int64_t = int; 12 | typedef uint64_t = int; 13 | typedef char = int; 14 | typedef float = double; 15 | -------------------------------------------------------------------------------- /lib/mavlink_dialect.dart: -------------------------------------------------------------------------------- 1 | library dart_mavlink; 2 | 3 | import 'dart:typed_data'; 4 | 5 | import 'package:dart_mavlink/mavlink_message.dart'; 6 | 7 | abstract class MavlinkDialect { 8 | int get version; 9 | 10 | MavlinkMessage? parse(int messageID, ByteData data); 11 | 12 | /// Returns CRC Extra of messageID. Returns -1 if unsupported messageID. 13 | int crcExtra(int messageID); 14 | } 15 | -------------------------------------------------------------------------------- /lib/crc.dart: -------------------------------------------------------------------------------- 1 | library dart_mavlink; 2 | 3 | class CrcX25 { 4 | static final _x25InitCrc = 0xffff; 5 | 6 | int _crc = _x25InitCrc; 7 | 8 | int get crc => _crc & 0xffff; 9 | 10 | void accumulate(int byte) { 11 | byte = byte & 0xff; // For cast as byte. 12 | 13 | int tmp = byte ^ (_crc &0xff); 14 | tmp &= 0xff; 15 | tmp ^= ((tmp<<4) & 0xff); 16 | 17 | _crc = (_crc>>8) ^ ((tmp<<8) &0xffff) ^ ((tmp <<3) &0xffff)^ (tmp>>4); 18 | } 19 | 20 | void accumulateString(String str) { 21 | for (var i in str.codeUnits) { 22 | accumulate(i); 23 | } 24 | } 25 | } 26 | -------------------------------------------------------------------------------- /.github/workflows/dart.yml: -------------------------------------------------------------------------------- 1 | # This workflow uses actions that are not certified by GitHub. 2 | # They are provided by a third-party and are governed by 3 | # separate terms of service, privacy policy, and support 4 | # documentation. 5 | 6 | name: Dart 7 | 8 | on: 9 | push: 10 | branches: [ "main" ] 11 | pull_request: 12 | branches: [ "main" ] 13 | 14 | jobs: 15 | build: 16 | runs-on: ubuntu-latest 17 | 18 | steps: 19 | - uses: actions/checkout@v3 20 | with: 21 | submodules: 'recursive' 22 | 23 | - uses: dart-lang/setup-dart@v1.3 24 | 25 | - name: Install dependencies 26 | run: dart pub get 27 | 28 | - name: Analyze project source 29 | run: dart analyze 30 | 31 | - name: Run tests 32 | run: dart test 33 | -------------------------------------------------------------------------------- /test/mavlink_serialize_v1_test.dart: -------------------------------------------------------------------------------- 1 | import 'dart:typed_data'; 2 | import 'package:dart_mavlink/dialects/common.dart'; 3 | import 'package:test/test.dart'; 4 | 5 | void main() { 6 | 7 | setUp(() { 8 | }); 9 | 10 | test('Serialize v1 packet', () async { 11 | var v = "FAKE_PARAM".codeUnits + [0, 0, 0, 0, 0, 0]; 12 | Uint8List.fromList(v); 13 | var msg = ParamSet(targetSystem: 1, 14 | targetComponent: 2, 15 | paramId: v, 16 | paramValue: 3, 17 | paramType: mavParamTypeInt32); 18 | var s = msg.serialize(); 19 | expect([ 20 | 0, 0, 64, 64, // param_value 21 | 1, // target_system 22 | 2, // target_component 23 | 70, 65, 75, 69, 95, 80, 65, 82, 65, 77, 0, 0, 0, 0, 0, 0, // param_value 24 | 6], // param_type 25 | s.buffer.asUint8List()); 26 | }); 27 | } 28 | -------------------------------------------------------------------------------- /example/parser.dart: -------------------------------------------------------------------------------- 1 | import 'dart:io'; 2 | import 'dart:math'; 3 | 4 | import 'package:dart_mavlink/mavlink.dart'; 5 | import 'package:dart_mavlink/dialects/common.dart'; 6 | 7 | void main() { 8 | var dialect = MavlinkDialectCommon(); 9 | var parser = MavlinkParser(dialect); 10 | 11 | parser.stream.listen((MavlinkFrame frm) { 12 | if (frm.message is Attitude) { 13 | var attitude = frm.message as Attitude; 14 | print('Yaw: ${attitude.yaw / pi * 180} [deg]'); 15 | } 16 | }); 17 | 18 | RawDatagramSocket.bind(InternetAddress.anyIPv4, 14550).then((RawDatagramSocket socket) { 19 | print('Listening.'); 20 | 21 | socket.listen((RawSocketEvent e) { 22 | if (e != RawSocketEvent.read) { 23 | return; 24 | } 25 | 26 | Datagram? d = socket.receive(); 27 | if (d == null) { 28 | return; 29 | } 30 | 31 | parser.parse(d.data); 32 | }); 33 | }); 34 | } 35 | -------------------------------------------------------------------------------- /analysis_options.yaml: -------------------------------------------------------------------------------- 1 | # This file configures the static analysis results for your project (errors, 2 | # warnings, and lints). 3 | # 4 | # This enables the 'recommended' set of lints from `package:lints`. 5 | # This set helps identify many issues that may lead to problems when running 6 | # or consuming Dart code, and enforces writing Dart using a single, idiomatic 7 | # style and format. 8 | # 9 | # If you want a smaller set of lints you can change this to specify 10 | # 'package:lints/core.yaml'. These are just the most critical lints 11 | # (the recommended set includes the core lints). 12 | # The core lints are also what is used by pub.dev for scoring packages. 13 | 14 | include: package:lints/recommended.yaml 15 | 16 | # Uncomment the following section to specify additional rules. 17 | 18 | # linter: 19 | # rules: 20 | # - camel_case_types 21 | 22 | # analyzer: 23 | # exclude: 24 | # - path/to/excluded/files/** 25 | 26 | # For more information about the core and recommended set of lints, see 27 | # https://dart.dev/go/core-lints 28 | 29 | # For additional information about configuring this file, see 30 | # https://dart.dev/guides/language/analysis-options 31 | -------------------------------------------------------------------------------- /example/parameter.dart: -------------------------------------------------------------------------------- 1 | import 'dart:io'; 2 | 3 | import 'package:dart_mavlink/mavlink.dart'; 4 | import 'package:dart_mavlink/dialects/common.dart'; 5 | 6 | void main() async { 7 | var dialect = MavlinkDialectCommon(); 8 | var parser = MavlinkParser(dialect); 9 | 10 | parser.stream.listen((MavlinkFrame frm) { 11 | if (frm.message is ParamValue) { 12 | var paramValue = frm.message as ParamValue; 13 | 14 | var terminatedIndex = paramValue.paramId.indexOf(0); 15 | terminatedIndex = terminatedIndex == -1 ? paramValue.paramId.length : terminatedIndex; 16 | var trimmed = paramValue.paramId.sublist(0, terminatedIndex); 17 | var paramId = String.fromCharCodes(trimmed); 18 | 19 | print('paramValue: ${paramValue.paramIndex} $paramId'); 20 | } 21 | }); 22 | 23 | var sequence = 0; 24 | var systemId = 255; 25 | var componentId = 1; 26 | var requestedParam = false; 27 | var socket = await RawDatagramSocket.bind(InternetAddress.anyIPv4, 14550); 28 | socket.listen((RawSocketEvent e) { 29 | if (e != RawSocketEvent.read) { 30 | return; 31 | } 32 | 33 | Datagram? d = socket.receive(); 34 | if (d == null) { 35 | return; 36 | } 37 | 38 | parser.parse(d.data); 39 | 40 | if (!requestedParam) { 41 | var paramRequestList = ParamRequestList( 42 | targetSystem: 1, 43 | targetComponent: 1 44 | ); 45 | var frm = MavlinkFrame.v1(sequence, systemId, componentId, paramRequestList); 46 | socket.send(frm.serialize(), d.address, d.port); 47 | 48 | requestedParam = true; 49 | } 50 | }); 51 | } 52 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | BSD 3-Clause License 2 | 3 | Copyright (c) 2022, Yota Ichino 4 | All rights reserved. 5 | 6 | Redistribution and use in source and binary forms, with or without 7 | modification, are permitted provided that the following conditions are met: 8 | 9 | 1. Redistributions of source code must retain the above copyright notice, this 10 | list of conditions and the following disclaimer. 11 | 12 | 2. Redistributions in binary form must reproduce the above copyright notice, 13 | this list of conditions and the following disclaimer in the documentation 14 | and/or other materials provided with the distribution. 15 | 16 | 3. Neither the name of the copyright holder nor the names of its 17 | contributors may be used to endorse or promote products derived from 18 | this software without specific prior written permission. 19 | 20 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 21 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 22 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 23 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 24 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 25 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 26 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 27 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 28 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 29 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -------------------------------------------------------------------------------- /test/mavlink_dialect/t03.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 3 4 | 3 5 | 6 | 7 | 8 | 9 | 10 | Description of ENUM_01 11 | USE ENUM_02 12 | 13 | Description of ENUM_01_ENTRY_00 14 | 15 | 16 | Description of ENUM_01_ENTRY_01 17 | 18 | 19 | 20 | Description of ENUM_02 21 | 22 | Description of ENUM_02_ENTRY_00 23 | 24 | 25 | Description of ENUM_02_ENTRY_01 26 | 27 | 28 | 29 | Description of ENUM_03. Contains different representations of integer values 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | -------------------------------------------------------------------------------- /test/mavlink_parser_v2_test.dart: -------------------------------------------------------------------------------- 1 | import 'package:dart_mavlink/dialects/common.dart'; 2 | import 'package:dart_mavlink/mavlink_parser.dart'; 3 | import 'package:dart_mavlink/mavlink_version.dart'; 4 | import 'package:test/test.dart'; 5 | import 'dart:typed_data'; 6 | 7 | void main() { 8 | MavlinkParser? parser; 9 | var d = Uint8List.fromList([ 10 | 0xfd, // Magick Number V2 11 | 0x09, // Payload Length 12 | 0x00, // Incompatibility Flags 13 | 0x00, // Compatibility Flags 14 | 0xdf, // Packet Sequence 15 | 0x01, // System ID 16 | 0x01, // Component ID 17 | 0x00, // Message ID,low (HEARTBEAT) 18 | 0x00, // Message ID,middle 19 | 0x00, // Message ID,hight 20 | 0x00, 0x00, 0x04, 0x03, // Custom Mode 21 | 0x02, // Type 22 | 0x0c, // autopilot 23 | 0x1d, // base mode 24 | 0x03, // system status 25 | 0x03, // mavlink version 26 | // End of payload 27 | 0x35, 0x36 // Checksum (Low byte, High byte) 28 | ]); 29 | 30 | setUp(() { 31 | parser = MavlinkParser(MavlinkDialectCommon()); 32 | }); 33 | 34 | test('Parse V2 packet', () async { 35 | parser!.parse(d); 36 | var frm = await parser!.stream.first; 37 | 38 | expect(frm.version, MavlinkVersion.v2); 39 | expect(frm.sequence, 0xdf); 40 | expect(frm.systemId, 0x01); 41 | expect(frm.componentId, 0x01); 42 | expect(frm.message is Heartbeat, isTrue); 43 | var hb = frm.message as Heartbeat; 44 | expect(hb.customMode, 0x03040000); 45 | expect(hb.type, mavTypeQuadrotor); 46 | expect(hb.autopilot, 0x0C); 47 | expect(hb.baseMode, 0x1D); 48 | expect(hb.systemStatus, 0x03); 49 | expect(hb.mavlinkVersion, 0x03); 50 | 51 | var ser = frm.serialize(); 52 | for (int i = 0; i < d.length; i++) { 53 | expect(d[i], ser[i]); 54 | } 55 | 56 | var hbModified = hb.copyWith(type: mavTypeFixedWing); 57 | expect(hbModified.type, mavTypeFixedWing); 58 | expect(hbModified.autopilot, 0x0C); 59 | }); 60 | 61 | test('Parse BATTERY_STATUS', () async { 62 | var d = Uint8List.fromList([ 63 | 0x00, 0x00, 0x00, 0x00, 0xff, 0xff, 0xff, 0xff, 0xff, 0x7f, 0xd2, 0x0f, 0xd2, 0x0f, 0xd2, 0x0f, 64 | 0xd2, 0x0f, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x9c, 0xff, 65 | 0x00, 0x01, 0x01, 0x64, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 66 | 0xff 67 | ]); 68 | var bs = BatteryStatus.parse(d.buffer.asByteData()); 69 | expect(bs.currentConsumed, 0); 70 | expect(bs.energyConsumed, -1); 71 | expect(bs.temperature, 32767); 72 | expect(bs.voltages[0], 4050); 73 | expect(bs.voltages[1], 4050); 74 | expect(bs.voltages[2], 4050); 75 | expect(bs.voltages[3], 4050); 76 | expect(bs.voltages[4], 65535); 77 | expect(bs.voltages[5], 65535); 78 | expect(bs.voltages[6], 65535); 79 | expect(bs.voltages[7], 65535); 80 | expect(bs.voltages[8], 65535); 81 | expect(bs.voltages[9], 65535); 82 | expect(bs.currentBattery, -100); 83 | expect(bs.batteryFunction, 1); 84 | expect(bs.type, 1); 85 | expect(bs.batteryRemaining, 100); 86 | expect(bs.voltagesExt[0], 65535); 87 | expect(bs.voltagesExt[1], 65535); 88 | expect(bs.voltagesExt[2], 65535); 89 | expect(bs.voltagesExt[3], 65535); 90 | expect(bs.mode, 0); 91 | expect(bs.faultBitmask, 0); 92 | 93 | var serialized = bs.serialize().buffer.asUint8List(); 94 | for (var i = 0; i < d.length; i++) { 95 | expect(serialized[i], d[i]); 96 | } 97 | }); 98 | } 99 | -------------------------------------------------------------------------------- /test/mavlink_parser_v1_test.dart: -------------------------------------------------------------------------------- 1 | import 'dart:async'; 2 | 3 | import 'package:dart_mavlink/mavlink_parser.dart'; 4 | import 'package:dart_mavlink/dialects/common.dart'; 5 | import 'package:test/test.dart'; 6 | import 'dart:typed_data'; 7 | 8 | void main() { 9 | MavlinkParser? parser; 10 | var d = Uint8List.fromList([ 11 | 0xFE, // Magick Number V1 12 | 0x09, // Payload Length 13 | 0xD2, // Packet Sequence 14 | 0x01, // System ID 15 | 0x01, // Component ID 16 | 0x00, // Message ID (HEARTBEAT) 17 | // Begin of payload 18 | 0x00, 0x00, 0x04, 0x03, // Custom Mode 19 | 0x02, // Type 20 | 0x0C, // autopilot 21 | 0x1D, // base mode 22 | 0x03, // system status 23 | 0x03, // mavlink version 24 | // End of payload 25 | 0x05, 0xEA // Checksum (Low byte, High byte) 26 | ]); 27 | 28 | setUp(() { 29 | parser = MavlinkParser(MavlinkDialectCommon()); 30 | }); 31 | 32 | test('Parse V1 packet', () async { 33 | parser!.parse(d); 34 | var frm = await parser!.stream.first; 35 | 36 | expect(frm.sequence, 0xD2); 37 | expect(frm.systemId, 0x01); 38 | expect(frm.componentId, 0x01); 39 | expect(frm.message is Heartbeat, isTrue); 40 | var hb = frm.message as Heartbeat; 41 | expect(hb.customMode, 0x03040000); 42 | expect(hb.type, mavTypeQuadrotor); 43 | expect(hb.autopilot, mavAutopilotPx4); 44 | expect(hb.baseMode, 0x1D); 45 | expect(hb.systemStatus, 0x03); 46 | expect(hb.mavlinkVersion, 0x03); 47 | 48 | var ser = frm.serialize(); 49 | for (int i = 0; i < d.length; i++) { 50 | expect(d[i], ser[i]); 51 | } 52 | }); 53 | 54 | test('Parse chuncked V1 packet', () async { 55 | var mid = d.length ~/ 2; 56 | var c1 = d.sublist(0, mid); 57 | var c2 = d.sublist(mid); 58 | 59 | parser!.parse(c1); 60 | parser!.parse(c2); 61 | 62 | var frm = await parser!.stream.first; 63 | expect(frm.sequence, 0xD2); 64 | expect(frm.systemId, 0x01); 65 | expect(frm.componentId, 0x01); 66 | expect(frm.message is Heartbeat, isTrue); 67 | }); 68 | 69 | test('Parse V1 packet with bad CRC', () async { 70 | var badCRC = Uint8List.fromList(d); 71 | badCRC[badCRC.length - 2] = 0x0B; 72 | badCRC[badCRC.length - 1] = 0xAD; 73 | parser!.parse(badCRC); 74 | 75 | var s = parser!.stream.timeout(Duration(milliseconds: 300)); 76 | expect(() async => await s.first, throwsA(TypeMatcher())); 77 | }); 78 | 79 | test('Parse a MAVLink packet contains float array', () async { 80 | var d = Uint8List.fromList([ 81 | // Header 82 | 0xfe, // Magick Number V1 83 | 0x29, // Payload Length 84 | 0x8b, // Packet Sequence 85 | 0x01, // System ID 86 | 0x01, // Component ID 87 | 0x8c, // Message ID (ACTUATOR_CONTROL_TARGET) 88 | // Begin of payload 89 | 0xe0, 0x8a, 0x1a, 0x07, 0x00, 0x00, 0x00, 0x00, // time_usec 90 | 0xda, 0x8d, 0xc5, 0xba, // controls[0] 91 | 0xc4, 0x50, 0x8c, 0x3a, // controls[1] 92 | 0x83, 0xbe, 0xa5, 0x39, // controls[2] 93 | 0x6f, 0x12, 0x83, 0x3a, // controls[3] 94 | 0x00, 0x00, 0x00, 0x00, // controls[4] 95 | 0x00, 0x00, 0x00, 0x00, // controls[5] 96 | 0x00, 0x00, 0x00, 0x00, // controls[6] 97 | 0x00, 0x00, 0x80, 0xbf, // controls[7] 98 | 0x00, // group_mlx 99 | // End of payload 100 | 0x31, 0x14 // Checksum (Low byte, High byte) 101 | ]); 102 | parser!.parse(d); 103 | 104 | var frm = await parser!.stream.first; 105 | expect(frm.sequence, 0x8b); 106 | expect(frm.systemId, 0x01); 107 | expect(frm.componentId, 0x01); 108 | expect(frm.message is ActuatorControlTarget, isTrue); 109 | var act = frm.message as ActuatorControlTarget; 110 | expect(act.timeUsec, 0x00000000071a8ae0); 111 | expect(act.controls[0], -0.0015072182286530733); 112 | expect(act.controls[1], 0.0010705222375690937); 113 | expect(act.controls[2], 0.00031613194732926786); 114 | expect(act.controls[3], 0.0010000000474974513); 115 | expect(act.controls[4], 0.0); 116 | expect(act.controls[5], 0.0); 117 | expect(act.controls[6], 0.0); 118 | expect(act.controls[7], -1.0); 119 | expect(act.groupMlx, 0x00); 120 | 121 | var byteData = act.serialize(); 122 | for (var i = 0; i < 41; i++) { 123 | expect(byteData.getUint8(i), d[6 + i]); 124 | } 125 | }); 126 | } 127 | -------------------------------------------------------------------------------- /lib/mavlink_frame.dart: -------------------------------------------------------------------------------- 1 | library dart_mavlink; 2 | 3 | import 'package:dart_mavlink/crc.dart'; 4 | 5 | import 'mavlink_version.dart'; 6 | import 'mavlink_message.dart'; 7 | import 'dart:typed_data'; 8 | 9 | class MavlinkFrame { 10 | static const mavlinkStxV1 = 0xFE; 11 | static const mavlinkStxV2 = 0xFD; 12 | 13 | final MavlinkVersion version; 14 | final int sequence; 15 | final int systemId; 16 | final int componentId; 17 | MavlinkMessage message; 18 | MavlinkFrame(this.version, this.sequence, this.systemId, this.componentId, this.message); 19 | 20 | /// Create MavlinkFrame for MAVLink version1. 21 | factory MavlinkFrame.v1(int sequence, int systemId, int componentId, MavlinkMessage message) { 22 | return MavlinkFrame(MavlinkVersion.v1, sequence, systemId, componentId, message); 23 | } 24 | 25 | /// Create MavlinkFrame for MAVLink version2. 26 | factory MavlinkFrame.v2(int sequence, int systemId, int componentId, MavlinkMessage message) { 27 | return MavlinkFrame(MavlinkVersion.v2, sequence, systemId, componentId, message); 28 | } 29 | 30 | Uint8List serialize() { 31 | if (version == MavlinkVersion.v1) { 32 | return _serializeV1(); 33 | } else { 34 | return _serializeV2(); 35 | } 36 | } 37 | 38 | Uint8List _serializeV1() { 39 | if (version != MavlinkVersion.v1) { 40 | throw UnsupportedError('Unexpected MAVLink version($version)'); 41 | } 42 | 43 | var payload = message.serialize(); 44 | var payloadLength = payload.lengthInBytes; 45 | 46 | var bytes = ByteData(8 + payloadLength); 47 | bytes.setUint8(0, mavlinkStxV1); 48 | bytes.setUint8(1, payloadLength); 49 | bytes.setUint8(2, sequence); 50 | bytes.setUint8(3, systemId); 51 | bytes.setUint8(4, componentId); 52 | bytes.setUint8(5, message.mavlinkMessageId); 53 | 54 | var crc = CrcX25(); 55 | crc.accumulate(payloadLength); 56 | crc.accumulate(sequence); 57 | crc.accumulate(systemId); 58 | crc.accumulate(componentId); 59 | crc.accumulate(message.mavlinkMessageId); 60 | 61 | var payloadBytes = payload.buffer.asUint8List(); 62 | for (var i = 0; i < payloadLength; i++) { 63 | bytes.setUint8(6 + i, payloadBytes[i]); 64 | crc.accumulate(payloadBytes[i]); 65 | } 66 | crc.accumulate(message.mavlinkCrcExtra); 67 | 68 | bytes.setUint8(bytes.lengthInBytes - 2, crc.crc & 0xff); 69 | bytes.setUint8(bytes.lengthInBytes - 1, (crc.crc >> 8) & 0xff); 70 | 71 | return bytes.buffer.asUint8List(); 72 | } 73 | 74 | Uint8List _serializeV2() { 75 | if (version != MavlinkVersion.v2) { 76 | throw UnsupportedError('Unexpected MAVLink version($version)'); 77 | } 78 | 79 | int incompatibilityFlags = 0; 80 | int compatibilityFlags = 0; 81 | var payload = message.serialize(); 82 | var payloadLength = payload.lengthInBytes; 83 | var messageIdBytes = [ 84 | message.mavlinkMessageId & 0xff, 85 | (message.mavlinkMessageId >> 8) & 0xff, 86 | (message.mavlinkMessageId >> 16) & 0xff 87 | ]; 88 | 89 | var bytes = ByteData(12 + payloadLength); 90 | bytes.setUint8(0, mavlinkStxV2); 91 | bytes.setUint8(1, payloadLength); 92 | bytes.setUint8(2, incompatibilityFlags); 93 | bytes.setUint8(3, compatibilityFlags); 94 | bytes.setUint8(4, sequence); 95 | bytes.setUint8(5, systemId); 96 | bytes.setUint8(6, componentId); 97 | bytes.setUint8(7, messageIdBytes[0]); 98 | bytes.setUint8(8, messageIdBytes[1]); 99 | bytes.setUint8(9, messageIdBytes[2]); 100 | 101 | var crc = CrcX25(); 102 | crc.accumulate(payloadLength); 103 | crc.accumulate(incompatibilityFlags); 104 | crc.accumulate(compatibilityFlags); 105 | crc.accumulate(sequence); 106 | crc.accumulate(systemId); 107 | crc.accumulate(componentId); 108 | crc.accumulate(messageIdBytes[0]); 109 | crc.accumulate(messageIdBytes[1]); 110 | crc.accumulate(messageIdBytes[2]); 111 | 112 | var payloadBytes = payload.buffer.asUint8List(); 113 | for (var i = 0; i < payloadLength; i++) { 114 | bytes.setUint8(10 + i, payloadBytes[i]); 115 | crc.accumulate(payloadBytes[i]); 116 | } 117 | crc.accumulate(message.mavlinkCrcExtra); 118 | 119 | bytes.setUint8(bytes.lengthInBytes - 2, crc.crc & 0xff); 120 | bytes.setUint8(bytes.lengthInBytes - 1, (crc.crc >> 8) & 0xff); 121 | 122 | return bytes.buffer.asUint8List(); 123 | } 124 | } 125 | -------------------------------------------------------------------------------- /test/generate_test.dart: -------------------------------------------------------------------------------- 1 | import 'package:test/test.dart'; 2 | 3 | import '../tool/generate.dart' as generate; 4 | 5 | void main() { 6 | test('Parse t00', () async { 7 | var dialectDoc = await generate.DialectDocument.parse('test/mavlink_dialect/t00.xml'); 8 | expect(dialectDoc.version, 0); 9 | expect(dialectDoc.dialect, 0); 10 | }); 11 | 12 | test('Parse t01, with include tag', () async { 13 | var dialectDoc = await generate.DialectDocument.parse('test/mavlink_dialect/t01.xml'); 14 | expect(dialectDoc.version, 1); 15 | expect(dialectDoc.dialect, 1); 16 | }); 17 | 18 | test('Parse t02, enums and messages are empty', () async { 19 | var dialectDoc = await generate.DialectDocument.parse('test/mavlink_dialect/t02.xml'); 20 | expect(dialectDoc.version, 2); 21 | expect(dialectDoc.dialect, 1); 22 | 23 | expect(dialectDoc.enums.length, 0); 24 | expect(dialectDoc.messages.length, 0); 25 | }); 26 | 27 | test('Parse t03, contains enums and messages', () async { 28 | var dialectDoc = await generate.DialectDocument.parse('test/mavlink_dialect/t03.xml'); 29 | expect(dialectDoc.version, 3); 30 | expect(dialectDoc.dialect, 3); 31 | 32 | expect(dialectDoc.enums.length, 4); 33 | 34 | var e = dialectDoc.enums.elementAt(0); 35 | expect(e.name, "ENUM_00"); 36 | expect(e.description, isNull); 37 | expect(e.entries, isNull); 38 | 39 | e = dialectDoc.enums.elementAt(1); 40 | expect(e.name, "ENUM_01"); 41 | expect(e.description, "Description of ENUM_01"); 42 | expect(e.deprecated?.since, '2021-11'); 43 | expect(e.deprecated?.replacedBy, 'ENUM_02'); 44 | expect(e.deprecated?.text, 'USE ENUM_02'); 45 | 46 | var entries = e.entries; 47 | expect(entries, isNotNull); 48 | expect(entries?.length, 2); 49 | expect(entries?.elementAt(0).value, 0); 50 | expect(entries?.elementAt(0).name, 'ENUM_01_ENTRY_00'); 51 | expect(entries?.elementAt(0).description, 'Description of ENUM_01_ENTRY_00'); 52 | expect(entries?.elementAt(1).value, 1); 53 | expect(entries?.elementAt(1).name, 'ENUM_01_ENTRY_01'); 54 | expect(entries?.elementAt(1).description, 'Description of ENUM_01_ENTRY_01'); 55 | 56 | e = dialectDoc.enums.elementAt(2); 57 | expect(e.name, "ENUM_02"); 58 | expect(e.description, "Description of ENUM_02"); 59 | expect(e.entries, isNotNull); 60 | 61 | e = dialectDoc.enums.elementAt(3); 62 | expect(e.name, "ENUM_03"); 63 | entries = e.entries; 64 | expect(entries?.elementAt(0).value, 1); 65 | expect(entries?.elementAt(1).value, 2); 66 | expect(entries?.elementAt(2).value, 4); 67 | expect(entries?.elementAt(3).value, 8); 68 | expect(entries?.elementAt(4).value, 16); 69 | expect(entries?.elementAt(5).value, 32); 70 | expect(entries?.elementAt(6).value, 64); 71 | expect(entries?.elementAt(7).value, 128); 72 | expect(entries?.elementAt(8).value, 1152921504606846976); 73 | expect(entries?.elementAt(9).value, 2305843009213693952); 74 | expect(entries?.elementAt(10).value, 4611686018427387904); 75 | }); 76 | 77 | test('Parse t04, name of enums is empty', () async { 78 | await generate.DialectDocument.parse('test/mavlink_dialect/t04.xml'); 79 | 80 | }); 81 | 82 | group('parsedMavlinkType', (){ 83 | test('test types', () { 84 | var t = generate.ParsedMavlinkType.parse('uint8_t'); 85 | expect(t.type, generate.BasicType.uint); 86 | expect(t.bit, 8); 87 | expect(t.arrayLength, 1); 88 | 89 | t = generate.ParsedMavlinkType.parse('uint8_t_mavlink_version'); 90 | expect(t.type, generate.BasicType.uint); 91 | expect(t.bit, 8); 92 | expect(t.arrayLength, 1); 93 | 94 | // Char as signed char; 95 | t = generate.ParsedMavlinkType.parse('char'); 96 | expect(t.type, generate.BasicType.int); 97 | expect(t.bit, 8); 98 | expect(t.arrayLength, 1); 99 | }); 100 | 101 | test('test array type', () { 102 | var t = generate.ParsedMavlinkType.parse('uint32_t[8]'); 103 | expect(t.type, generate.BasicType.uint); 104 | expect(t.bit, 32); 105 | expect(t.arrayLength, 8); 106 | 107 | t = generate.ParsedMavlinkType.parse('char[25]'); 108 | expect(t.type, generate.BasicType.int); 109 | expect(t.bit, 8); 110 | expect(t.arrayLength, 25); 111 | }); 112 | }); 113 | 114 | group('DialectMessage', () { 115 | test('Check calculating methods', () async { 116 | var dlctDoc = await generate.DialectDocument.parse('mavlink/message_definitions/v1.0/minimal.xml'); 117 | var msgs = dlctDoc.messages.toList(); 118 | 119 | var dlctMessage = msgs[0]; 120 | expect(dlctMessage.name, "HEARTBEAT"); 121 | expect(dlctMessage.calculateCrcExtra(), 50); 122 | expect(dlctMessage.calculateEncodedLength(), 9); 123 | 124 | // Test a message that contains array fields. 125 | dlctMessage = msgs[1]; 126 | expect(dlctMessage.name, "PROTOCOL_VERSION"); 127 | expect(dlctMessage.calculateCrcExtra(), 217); 128 | expect(dlctMessage.calculateEncodedLength(), 22); 129 | }); 130 | }); 131 | } 132 | -------------------------------------------------------------------------------- /lib/mavlink_message.dart: -------------------------------------------------------------------------------- 1 | library dart_mavlink; 2 | 3 | import 'dart:typed_data'; 4 | 5 | abstract class MavlinkMessage { 6 | factory MavlinkMessage.parse(ByteData data) { 7 | throw UnimplementedError('Implement this constructor on inheriting class'); 8 | } 9 | 10 | int get mavlinkMessageId; 11 | int get mavlinkCrcExtra; 12 | 13 | ByteData serialize(); 14 | 15 | static Int8List asInt8List(ByteData data, int offsetInBytes, int length) { 16 | Int8List ret = Int8List(length); 17 | for (var i = 0; i < length; i++) { 18 | ret[i] = data.getInt8(offsetInBytes + i); 19 | } 20 | 21 | return ret; 22 | } 23 | 24 | static Uint8List asUint8List(ByteData data, int offsetInBytes, int length) { 25 | Uint8List ret = Uint8List(length); 26 | for (var i = 0; i < length; i++) { 27 | ret[i] = data.getUint8(offsetInBytes + i); 28 | } 29 | 30 | return ret; 31 | } 32 | 33 | static Int16List asInt16List(ByteData data, int offsetInBytes, int length, [Endian endian=Endian.little]) { 34 | Int16List ret = Int16List(length); 35 | for (var i = 0; i < length; i++) { 36 | ret[i] = data.getInt16(offsetInBytes + (i * 2), endian); 37 | } 38 | 39 | return ret; 40 | } 41 | 42 | static Uint16List asUint16List(ByteData data, int offsetInBytes, int length, [Endian endian=Endian.little]) { 43 | Uint16List ret = Uint16List(length); 44 | for (var i = 0; i < length; i++) { 45 | ret[i] = data.getUint16(offsetInBytes + (i * 2), endian); 46 | } 47 | 48 | return ret; 49 | } 50 | 51 | static Int32List asInt32List(ByteData data, int offsetInBytes, int length, [Endian endian=Endian.little]) { 52 | Int32List ret = Int32List(length); 53 | for (var i = 0; i < length; i++) { 54 | ret[i] = data.getInt32(offsetInBytes + (i * 4), endian); 55 | } 56 | 57 | return ret; 58 | } 59 | 60 | static Uint32List asUint32List(ByteData data, int offsetInBytes, int length, [Endian endian=Endian.little]) { 61 | Uint32List ret = Uint32List(length); 62 | for (var i = 0; i < length; i++) { 63 | ret[i] = data.getUint32(offsetInBytes + (i * 4), endian); 64 | } 65 | 66 | return ret; 67 | } 68 | 69 | static Int64List asInt64List(ByteData data, int offsetInBytes, int length, [Endian endian=Endian.little]) { 70 | Int64List ret = Int64List(length); 71 | for (var i = 0; i < length; i++) { 72 | ret[i] = data.getInt64(offsetInBytes + (i * 8), endian); 73 | } 74 | 75 | return ret; 76 | } 77 | 78 | static Uint64List asUint64List(ByteData data, int offsetInBytes, int length, [Endian endian=Endian.little]) { 79 | Uint64List ret = Uint64List(length); 80 | for (var i = 0; i < length; i++) { 81 | ret[i] = data.getUint64(offsetInBytes + (i * 8), endian); 82 | } 83 | 84 | return ret; 85 | } 86 | 87 | static Float32List asFloat32List(ByteData data, int offsetInBytes, int length, [Endian endian=Endian.little]) { 88 | Float32List ret = Float32List(length); 89 | for (var i = 0; i < length; i++) { 90 | ret[i] = data.getFloat32(offsetInBytes + (i * 4), endian); 91 | } 92 | 93 | return ret; 94 | } 95 | 96 | static Float64List asFloat64List(ByteData data, int offsetInBytes, int length, [Endian endian=Endian.little]) { 97 | Float64List ret = Float64List(length); 98 | for (var i = 0; i < length; i++) { 99 | ret[i] = data.getFloat64(offsetInBytes + (i * 8), endian); 100 | } 101 | 102 | return ret; 103 | } 104 | 105 | static void setInt8List(ByteData data, int offsetByte, List list) { 106 | int len = list.length; 107 | for (int i = 0; i < len; i++) { 108 | data.setInt8(offsetByte + i, list[i]); 109 | } 110 | } 111 | 112 | static void setUint8List(ByteData data, int offsetByte, List list) { 113 | int len = list.length; 114 | for (int i = 0; i < len; i++) { 115 | data.setUint8(offsetByte + i, list[i]); 116 | } 117 | } 118 | 119 | static void setInt16List(ByteData data, int offsetByte, List list, [Endian endian=Endian.little]) { 120 | int len = list.length; 121 | for (int i = 0; i < len; i++) { 122 | data.setInt16(offsetByte + (i * 2), list[i], endian); 123 | } 124 | } 125 | 126 | static void setUint16List(ByteData data, int offsetByte, List list, [Endian endian=Endian.little]) { 127 | int len = list.length; 128 | for (int i = 0; i < len; i++) { 129 | data.setUint16(offsetByte + (i * 2), list[i], endian); 130 | } 131 | } 132 | 133 | static void setInt32List(ByteData data, int offsetByte, List list, [Endian endian=Endian.little]) { 134 | int len = list.length; 135 | for (int i = 0; i < len; i++) { 136 | data.setInt32(offsetByte + (i * 4), list[i], endian); 137 | } 138 | } 139 | 140 | static void setUint32List(ByteData data, int offsetByte, List list, [Endian endian=Endian.little]) { 141 | int len = list.length; 142 | for (int i = 0; i < len; i++) { 143 | data.setUint32(offsetByte + (i * 4), list[i], endian); 144 | } 145 | } 146 | 147 | static void setInt64List(ByteData data, int offsetByte, List list, [Endian endian=Endian.little]) { 148 | int len = list.length; 149 | for (int i = 0; i < len; i++) { 150 | data.setInt64(offsetByte + (i * 8), list[i], endian); 151 | } 152 | } 153 | 154 | static void setUint64List(ByteData data, int offsetByte, List list, [Endian endian=Endian.little]) { 155 | int len = list.length; 156 | for (int i = 0; i < len; i++) { 157 | data.setUint64(offsetByte + (i * 8), list[i], endian); 158 | } 159 | } 160 | 161 | static void setFloat32List(ByteData data, int offsetByte, List list, [Endian endian=Endian.little]) { 162 | int len = list.length; 163 | for (int i = 0; i < len; i++) { 164 | data.setFloat32(offsetByte + (i * 4), list[i], endian); 165 | } 166 | } 167 | 168 | static void setFloat64List(ByteData data, int offsetByte, List list, [Endian endian=Endian.little]) { 169 | int len = list.length; 170 | for (int i = 0; i < len; i++) { 171 | data.setFloat64(offsetByte + (i * 8), list[i], endian); 172 | } 173 | } 174 | } 175 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # dart_mavlink 2 | 3 | This is a Dart package for parsing and serializing MAVLink v1/v2 packets. See `example/sitl_test.dart` for example usage. Some high level concepts are covered below. 4 | 5 | ## Basic Usage 6 | 7 | Import the library. 8 | 9 | ```dart 10 | import 'package:dart_mavlink/mavlink.dart'; 11 | import 'package:dart_mavlink/dialects/common.dart'; 12 | ``` 13 | 14 | ### Parsing Messages 15 | 16 | Each dialect.xml will have a corresponding class in the library. Select which one you want to use, and pass that dialect to a MavlinkParser object. 17 | 18 | ```dart 19 | var parser = MavlinkParser(MavlinkDialectCommon()); // Create the parser with the MavlinkCommon dialect 20 | ``` 21 | 22 | The ```MavlinkParser``` has a Stream that emits ```MavlinkFrame``` objects when it successfully decodes one from parsed data. Inside the MavlinkFrame is a ```MavlinkMessage``` object which we can feed into a switch statement to do things based on when we receive specific kinds of messages. For more detail on structure of mavlink frames/messages see [Mavlink Packet Serialization](https://mavlink.io/en/guide/serialization.html) 23 | 24 | ```dart 25 | parser.stream.listen((MavlinkFrame frame) { 26 | print("Parsed a frame from Sysid:CompID ${frame.systemId}:${frame.componentId} containing a ${frame.message.runtimeType} message"); 27 | MavlinkMessage message = frame.message; 28 | var messageType = frame.message.runtimeType; 29 | switch (messageType) { 30 | case Heartbeat: 31 | doSomethingWithHeartbeat(message as Heartbeat); 32 | break; 33 | case Statustext: 34 | doSomethingWithStatusText(message as Statustext); 35 | break; 36 | case BatteryStatus: 37 | doSomethingWithBatteryStatus(message as BatteryStatus) 38 | break; 39 | default: 40 | break; 41 | } 42 | }); 43 | 44 | void doSomethingWithBatteryStatus(BatteryStatus msg){ 45 | print("Got a BatteryStatus message! Charge State: ${msg.chargeState}"); 46 | } 47 | ``` 48 | 49 | We can now feed data into the parser. It can come from anywhere, typically a TCP socket. In this example, a byte list is used: 50 | 51 | ```dart 52 | var sampleBatteryStatus = Uint8List.fromList([ 53 | 0x00, 0x00, 0x00, 0x00, 0xff, 0xff, 0xff, 0xff, 0xff, 0x7f, 0xd2, 0x0f, 0xd2, 0x0f, 0xd2, 0x0f, 54 | 0xd2, 0x0f, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x9c, 0xff, 55 | 0x00, 0x01, 0x01, 0x64, 0x00, 0x00, 0x00, 0x00, 0x01, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 56 | 0xff 57 | ]); 58 | 59 | parser.parse(sampleBatteryStatus); 60 | ``` 61 | 62 | This will cause the ```doSomethingWithBatteryStatus()``` function to execute. 63 | 64 | ### Creating/Serializing/Sending Messages 65 | 66 | Each message definied in the dialect has a corresponding class. For example, to create a [REQUEST_DATA_STREAM](https://mavlink.io/en/messages/common.html#REQUEST_DATA_STREAM) message, construct the message: 67 | 68 | ```dart 69 | RequestDataStream msg = RequestDataStream(reqMessageRate: 1, targetSystem: 1, targetComponent: 1, reqStreamId: mavDataStreamAll, startStop: 1); 70 | ``` 71 | 72 | or to create a [COMMAND_LONG](https://mavlink.io/en/messages/common.html#COMMAND_LONG) requesting that the vehicle change to GUIDED mode (Mode 4 is GUIDED for Ardupilot vehicles): 73 | 74 | ```dart 75 | CommandLong command = CommandLong( 76 | command: mavCmdDoSetMode, 77 | param1: 1, 78 | param2: 4, 79 | param3: 0, 80 | param4: 0, 81 | param5: 0, 82 | param6: 0, 83 | param7: 0, 84 | targetSystem: 1, 85 | targetComponent: 1, 86 | confirmation: 0); 87 | ``` 88 | 89 | The message classes are immutable. If you need to change a value in the message, but don't want to copy all the other fields, a ```copyFrom``` method is provided for all messages. 90 | 91 | ```dart 92 | CommandLong firstCommand = CommandLong( 93 | command: mavCmdDoSetMode, 94 | param1: 1, 95 | param2: 4, 96 | param3: 0, 97 | param4: 0, 98 | param5: 0, 99 | param6: 0, 100 | param7: 0, 101 | targetSystem: 1, 102 | targetComponent: 1, 103 | confirmation: 0); 104 | 105 | CommandLong modifiedCommand = firstCommand.copyWith(param2: 10); 106 | ``` 107 | 108 | To send the message we first wrap the message in a MavlinkFrame specifying the systemID and componentID. In this case, a Mavlink2 frame. Mavlink1 is also supported. 109 | 110 | ```dart 111 | var rawRpm = RawRpm(frequency: 1.0, index: 1); 112 | MavlinkFrame frame = MavlinkFrame.v2(0, 1, 255, rawRpm); 113 | ``` 114 | 115 | We can now serialize this frame to a compact binary representation and push it to whatever transport is useful; in this case a TCP socket. 116 | 117 | ``` dart 118 | Socket sitlSocket = await Socket.connect("127.0.0.1", 5760); 119 | sitlSocket.add(frame.serialize()); 120 | ``` 121 | 122 | ## Example Control of Simulated Ardupilot Copter 123 | 124 | An example script has been provided that sends/receives commands from a simulated Ardupilot quadcopter. The specific details of using/flying an Ardupilot vehicle are beyond the scope of this library, but their conveniently pre-compiled Software-in-the-Loop (SITL) binaries are an easy way to show how the libary might be used to command one. 125 | 126 | Download the Ardupilot SITL binary and a default parameter file from the Ardupilot github, give it executable permission, then run it. This is assuming x86-64 Linux, but it should work the same in WSL 127 | 128 | ``` shell 129 | mkdir example/ardupilot_sitl && cd example/ardupilot_sitl 130 | wget https://firmware.ardupilot.org/Copter/stable-4.5.7/SITL_x86_64_linux_gnu/arducopter 131 | wget https://raw.githubusercontent.com/ArduPilot/ardupilot/42ad2a7911f1239e9320ca9ba67877d09840545f/Tools/autotest/default_params/copter.parm 132 | chmod +x arducopter 133 | ./arducopter --defaults ./copter.parm --model + --sim-address 127.0.0.1 134 | ``` 135 | 136 | In another window, or in your IDE, run the `sitl_test.dart` example in the examples folder 137 | 138 | ``` shell 139 | dart ./example/sitl_test.dart 140 | ``` 141 | 142 | You will see the following sequence in the output of the sitl_test script: 143 | 144 | - Wait for vehicle to boot by monitoring for a STATUSTEXT mavlink message 145 | - Change the mode from STABILIZE to GUIDED 146 | - Wait for pre-arm checks to pass (will take 30-60 seconds) 147 | - Arm the vehicle 148 | - Command vehicle to takeoff ot 30 meters 149 | - Wait 30 seconds 150 | - Command the vehicle to Return To Land (RTL) 151 | 152 | See the comments in the script for more detail on usage. 153 | -------------------------------------------------------------------------------- /lib/mavlink_parser.dart: -------------------------------------------------------------------------------- 1 | library dart_mavlink; 2 | 3 | import 'dart:async'; 4 | import 'dart:typed_data'; 5 | 6 | import 'crc.dart'; 7 | import 'mavlink_dialect.dart'; 8 | import 'mavlink_frame.dart'; 9 | import 'mavlink_version.dart'; 10 | 11 | enum _ParserState { 12 | init, 13 | waitPayloadLength, 14 | waitIncompatibilityFalgs, 15 | waitCompatibilityFlags, 16 | waitPacketSequence, 17 | waitSystemId, 18 | waitComponentId, 19 | waitMessageIdLow, 20 | waitMessageIdMiddle, 21 | waitMessageIdHigh, 22 | waitPayloadEnd, 23 | waitCrcLowByte, 24 | waitCrcHighByte, 25 | } 26 | 27 | class MavlinkParser { 28 | static const _mavlinkMaximumPayloadSize = 255; 29 | static const _mavlinkIflagSigned = 0x01; 30 | 31 | final _streamController = StreamController(); 32 | 33 | _ParserState _state = _ParserState.init; 34 | 35 | MavlinkVersion _version = MavlinkVersion.v1; 36 | int _payloadLength = -1; 37 | int _incompatibilityFlags = -1; 38 | int _compatibilityFlags = -1; 39 | int _sequence = -1; 40 | int _systemId = -1; 41 | int _componentId = -1; 42 | int _messageIdLow = -1; 43 | int _messageIdMiddle = -1; 44 | int _messageIdHigh = -1; 45 | int _messageId = -1; 46 | final Uint8List _payload = Uint8List(_mavlinkMaximumPayloadSize); 47 | int _payloadCursor = -1; 48 | int _crcLowByte = -1; 49 | int _crcHighByte = -1; 50 | 51 | final MavlinkDialect _dialect; 52 | 53 | MavlinkParser(this._dialect); 54 | 55 | void _resetContext() { 56 | _version = MavlinkVersion.v1; 57 | _payloadLength = -1; 58 | _incompatibilityFlags = -1; 59 | _compatibilityFlags = -1; 60 | _sequence = -1; 61 | _systemId = -1; 62 | _componentId = -1; 63 | _messageIdLow = -1; 64 | _messageIdMiddle = -1; 65 | _messageIdHigh = -1; 66 | _messageId = -1; 67 | _payloadCursor = -1; 68 | _crcLowByte = -1; 69 | _crcHighByte = -1; 70 | } 71 | 72 | bool _checkCRC() { 73 | var header = (_version == MavlinkVersion.v1) 74 | ? [_payloadLength, _sequence, _systemId, _componentId, _messageId] 75 | : [_payloadLength, _incompatibilityFlags, _compatibilityFlags, _sequence, _systemId, _componentId, _messageIdLow, _messageIdMiddle, _messageIdHigh]; 76 | 77 | var crc = CrcX25(); 78 | 79 | for (int d in header) { 80 | crc.accumulate(d & 0xff); 81 | } 82 | 83 | for (int i = 0; i < _payloadLength; i++) { 84 | var d = _payload[i]; 85 | crc.accumulate(d & 0xff); 86 | } 87 | 88 | var crcExt = _dialect.crcExtra(_messageId); 89 | if (crcExt == -1) { 90 | return false; 91 | } 92 | crc.accumulate(crcExt); 93 | 94 | return crc.crc == ((_crcHighByte) << 8) ^ (_crcLowByte); 95 | } 96 | 97 | void parse(Uint8List data) { 98 | for (int d in data) { 99 | switch (_state) { 100 | case _ParserState.init: 101 | switch (d) { 102 | case MavlinkFrame.mavlinkStxV1: 103 | _version = MavlinkVersion.v1; 104 | _state = _ParserState.waitPayloadLength; 105 | break; 106 | case MavlinkFrame.mavlinkStxV2: 107 | _version = MavlinkVersion.v2; 108 | _state = _ParserState.waitPayloadLength; 109 | break; 110 | default: 111 | // Skip the byte 112 | } 113 | break; 114 | case _ParserState.waitPayloadLength: 115 | _payloadLength = d; 116 | if (_version == MavlinkVersion.v1) { 117 | _state = _ParserState.waitPacketSequence; 118 | } else { 119 | // For MAVLink v2 120 | _state = _ParserState.waitIncompatibilityFalgs; 121 | } 122 | break; 123 | case _ParserState.waitIncompatibilityFalgs: 124 | // For MAVLink v2 125 | _incompatibilityFlags = d; 126 | _state = _ParserState.waitCompatibilityFlags; 127 | break; 128 | case _ParserState.waitCompatibilityFlags: 129 | // For MAVLink v2 130 | _compatibilityFlags = d; 131 | _state = _ParserState.waitPacketSequence; 132 | break; 133 | case _ParserState.waitPacketSequence: 134 | _sequence = d; 135 | _state = _ParserState.waitSystemId; 136 | break; 137 | case _ParserState.waitSystemId: 138 | _systemId = d; 139 | _state = _ParserState.waitComponentId; 140 | break; 141 | case _ParserState.waitComponentId: 142 | _componentId = d; 143 | if (_version == MavlinkVersion.v1) { 144 | _state = _ParserState.waitMessageIdHigh; 145 | } else { 146 | _state = _ParserState.waitMessageIdLow; 147 | } 148 | break; 149 | case _ParserState.waitMessageIdLow: 150 | // For MAVLink v2 151 | _messageIdLow = d; 152 | _state = _ParserState.waitMessageIdMiddle; 153 | break; 154 | case _ParserState.waitMessageIdMiddle: 155 | // For MAVLink v2 156 | _messageIdMiddle = d; 157 | _state = _ParserState.waitMessageIdHigh; 158 | break; 159 | case _ParserState.waitMessageIdHigh: 160 | if (_version == MavlinkVersion.v1) { 161 | _messageId = d; 162 | } else { 163 | // For MAVLink v2 164 | _messageIdHigh = d; 165 | _messageId = (_messageIdHigh << 16) ^ (_messageIdMiddle << 8) ^ _messageIdLow; 166 | } 167 | 168 | if (_payloadLength == 0) { 169 | _state = _ParserState.waitCrcLowByte; 170 | } else { 171 | _state = _ParserState.waitPayloadEnd; 172 | _payloadCursor = 0; 173 | } 174 | break; 175 | case _ParserState.waitPayloadEnd: 176 | if (_payloadCursor < _payloadLength) { 177 | _payload[_payloadCursor++] = d; 178 | } 179 | 180 | if (_payloadCursor == _payloadLength) { 181 | _state = _ParserState.waitCrcLowByte; 182 | } 183 | break; 184 | case _ParserState.waitCrcLowByte: 185 | _crcLowByte = d; 186 | _state = _ParserState.waitCrcHighByte; 187 | break; 188 | case _ParserState.waitCrcHighByte: 189 | _crcHighByte = d; 190 | 191 | if (_version == MavlinkVersion.v2) { 192 | if (_incompatibilityFlags == _mavlinkIflagSigned) { 193 | // TODO Handle the Signature bits. 194 | _resetContext(); 195 | _state = _ParserState.init; 196 | break; 197 | } 198 | } 199 | 200 | _addMavlinkFrameToStream(); 201 | 202 | _resetContext(); 203 | _state = _ParserState.init; 204 | break; 205 | } 206 | } 207 | } 208 | 209 | bool _addMavlinkFrameToStream() { 210 | // check CRC bytes. 211 | if (!_checkCRC()) { 212 | // The MAVLink packet is a bad CRC. 213 | // Ignore the MAVLink packet. 214 | return false; 215 | } 216 | 217 | var message = _dialect.parse(_messageId, _payload.buffer.asByteData(0, _payloadLength)); 218 | if (message == null) { 219 | return false; 220 | } 221 | 222 | // Got a Mavlink Frame data. 223 | var frame = MavlinkFrame(_version, _sequence, _systemId, _componentId, message); 224 | _streamController.add(frame); 225 | return true; 226 | } 227 | 228 | Stream get stream => _streamController.stream; 229 | } 230 | -------------------------------------------------------------------------------- /example/sitl_test.dart: -------------------------------------------------------------------------------- 1 | import 'dart:io'; 2 | import 'dart:async'; 3 | import 'dart:convert' show ascii; 4 | import 'package:dart_mavlink/mavlink.dart'; 5 | import 'package:dart_mavlink/dialects/common.dart'; 6 | 7 | const myComponentId = mavTypeGcs; 8 | const mySystemId = 255; 9 | int sequence = 0; 10 | Socket? sitlSocket; 11 | SysStatus? lastSysStatus; 12 | Heartbeat? lastHeartbeat; 13 | VfrHud? lastVfrHud; 14 | Attitude? lastAttitude; 15 | GlobalPositionInt? lastGlobalPositionInt; 16 | bool ardupilotReady = false; 17 | 18 | void main() async { 19 | var dialect = MavlinkDialectCommon(); // Declare which dialect we're going to use 20 | var parser = MavlinkParser(dialect); // Create the parser with the selected dialect 21 | sitlSocket = await Socket.connect("127.0.0.1", 5760); // Connect to the device. TCP in this case 22 | 23 | // Configure the socket to pass it's received data to the parser 24 | sitlSocket?.listen((data) { 25 | parser.parse(data); 26 | }, onError: (error) { 27 | print("Error $error when listening. Exiting."); 28 | exit(0); 29 | }, onDone: () { 30 | print("Socket closed, Exiting!"); 31 | exit(0); 32 | }); 33 | 34 | // The parser has a Stream object that emits MavlinkFrames whenever it successfully parses a frame 35 | // Here we setup callbacks to do actions based on what type of MavlinkMessage is in the message field of the frame 36 | // See https://mavlink.io/en/guide/serialization.html#mavlink2_packet_format for more info on what info is in the frame vs. the message. 37 | parser.stream.listen((MavlinkFrame frame) { 38 | // print("Parsed frame from Sysid:CompID ${frame.systemId}:${frame.componentId} containing a ${frame.message.runtimeType} message"); 39 | MavlinkMessage message = frame.message; 40 | var messageType = frame.message.runtimeType; 41 | switch (messageType) { 42 | case Heartbeat: 43 | handleHeartbeat(message as Heartbeat); 44 | break; 45 | case Statustext: 46 | handleStatusText(message as Statustext); 47 | break; 48 | case CommandAck: 49 | handleCommandAck(message as CommandAck); 50 | break; 51 | case SysStatus: 52 | lastSysStatus = message as SysStatus; 53 | break; 54 | case VfrHud: 55 | lastVfrHud = message as VfrHud; 56 | break; 57 | case GlobalPositionInt: 58 | lastGlobalPositionInt = message as GlobalPositionInt; 59 | break; 60 | default: 61 | // print("Got $messageType from System: ${frame.systemId} Component: ${frame.componentId}"); 62 | } 63 | }); 64 | 65 | // Setup a timer to periodically send a heartbeat to the simulated device, as well as print out some info 66 | Timer.periodic(Duration(seconds: 1), (_) { 67 | sendHeartbeat(); 68 | printSystemState(); 69 | }); 70 | 71 | // Wait for Ardupilot to boot up. handleStatusText will set the bool when it hears that APM is ready. 72 | // Theres probably a more elegent way to check for this but this works for demonstration. 73 | await Future.doWhile(() async { 74 | await Future.delayed(Duration(seconds: 1)); 75 | if (ardupilotReady) { 76 | return false; 77 | } 78 | return true; 79 | }); 80 | 81 | // Ask the device to stream data to us 82 | requestDataStreamAll(); 83 | 84 | // Set the mode to Guided 85 | setModeGuided(); 86 | 87 | // Wait here while the device does it's prearm checks 88 | await Future.doWhile(() async { 89 | await Future.delayed(Duration(seconds: 1)); 90 | // For Ardupilot, we can monitor the SysStatus message and look at the prearm check bitfield to determine when it's ready to be armed 91 | if (((lastSysStatus?.onboardControlSensorsHealth ?? 0) & mavSysStatusPrearmCheck) > 0) { 92 | print("prearm checks passed, ready to arm"); 93 | return false; 94 | } 95 | return true; 96 | }); 97 | 98 | // arm the device 99 | sendArmCommand(); 100 | // Send a takeoff command 101 | sendTakeoffCommand(); 102 | 103 | // Wait 30 seconds and then put it in land mode. 104 | await Future.delayed(Duration(seconds: 30)); 105 | setModeRTL(); 106 | } 107 | 108 | // Requests that the autopilot sends all the "standard" data streams. 109 | void requestDataStreamAll() { 110 | var msg = RequestDataStream(reqMessageRate: 1, targetSystem: 1, targetComponent: 1, reqStreamId: mavDataStreamAll, startStop: 1); 111 | sendMessage(msg); 112 | } 113 | 114 | void setModeGuided() { 115 | print("Setting mode to guided"); 116 | var command = CommandLong( 117 | command: mavCmdDoSetMode, 118 | param1: 1, 119 | param2: 4, 120 | param3: 0, 121 | param4: 0, 122 | param5: 0, 123 | param6: 0, 124 | param7: 0, 125 | targetSystem: 1, 126 | targetComponent: 1, 127 | confirmation: 0); 128 | sendMessage(command); 129 | } 130 | 131 | void setModeRTL() { 132 | print("Setting mode to RTL"); 133 | var command = CommandLong( 134 | command: mavCmdDoSetMode, 135 | param1: 1, 136 | param2: 6, 137 | param3: 0, 138 | param4: 0, 139 | param5: 0, 140 | param6: 0, 141 | param7: 0, 142 | targetSystem: 1, 143 | targetComponent: 1, 144 | confirmation: 0); 145 | sendMessage(command); 146 | } 147 | 148 | void sendHeartbeat() { 149 | Heartbeat heartbeat = 150 | Heartbeat(type: mavTypeGeneric, autopilot: mavAutopilotGeneric, baseMode: 0, customMode: 0, systemStatus: mavStateActive, mavlinkVersion: 2); 151 | sendMessage(heartbeat); 152 | } 153 | 154 | void sendArmCommand() { 155 | print("Sending arm command"); 156 | var command = CommandLong( 157 | command: mavCmdComponentArmDisarm, 158 | param1: 1, 159 | param2: 0, 160 | param3: 0, 161 | param4: 0, 162 | param5: 0, 163 | param6: 0, 164 | param7: 0, 165 | targetSystem: 1, 166 | targetComponent: 1, 167 | confirmation: 0); 168 | sendMessage(command); 169 | } 170 | 171 | void sendTakeoffCommand() { 172 | print("Sending takeoff command"); 173 | var command = CommandLong( 174 | command: mavCmdNavTakeoff, 175 | param1: 0, 176 | param2: 0, 177 | param3: 0, 178 | param4: 0, 179 | param5: 0, 180 | param6: 0, 181 | param7: 30, 182 | targetSystem: 1, 183 | targetComponent: 1, 184 | confirmation: 0); 185 | sendMessage(command); 186 | } 187 | 188 | void handleHeartbeat(Heartbeat msg) { 189 | lastHeartbeat = msg; 190 | print("Heartbeat: BaseMode: ${msg.baseMode} State: ${msg.systemStatus} CustomMode: ${msg.customMode}"); 191 | } 192 | 193 | void handleStatusText(Statustext msg) { 194 | String decoded = convertMavlinkCharListToString(msg.text); 195 | print("Status Text: $decoded"); 196 | if (!ardupilotReady && decoded == "ArduPilot Ready") { 197 | ardupilotReady = true; 198 | } 199 | } 200 | 201 | void handleBatteryStatus(BatteryStatus msg) { 202 | print("Handling battery Status"); 203 | } 204 | 205 | void handleCommandAck(CommandAck msg) { 206 | print("Command ack: Command ${msg.command} Result: ${msg.result}"); 207 | } 208 | 209 | // Helper function that packs a supplied MavlinkMessage into a MavlinkFrame, and increments the sequence field 210 | void sendMessage(MavlinkMessage msg) { 211 | var frame = MavlinkFrame.v2(sequence, mySystemId, myComponentId, msg); 212 | sitlSocket?.add(frame.serialize()); 213 | sequence = (sequence + 1) % 255; // Sequence is a uint8_t, store the actual sequence count locally and truncate it to 1 byte when packing in the message 214 | } 215 | 216 | // Helper function that converts "char arrays" stored in mavlink messages that are sent as lists of ints into Strings, trimming out padding and such. 217 | String convertMavlinkCharListToString(List? charList) { 218 | if (charList == null) { 219 | return ""; 220 | } 221 | List trimmedList = []; 222 | for (int character in charList) { 223 | if (character != 0x00 && character > 0) { 224 | trimmedList.add(character); 225 | } 226 | } 227 | return ascii.decode(trimmedList); 228 | } 229 | 230 | void printSystemState() { 231 | var agl = (lastGlobalPositionInt?.relativeAlt ?? 0) / 1000; 232 | var msl = (lastGlobalPositionInt?.alt ?? 0) / 1000; 233 | print("Alt AGL: ${agl.toStringAsFixed(1)} m \t Alt MSL: ${msl.toStringAsFixed(1)} m"); 234 | } 235 | -------------------------------------------------------------------------------- /lib/dialects/icarous.dart: -------------------------------------------------------------------------------- 1 | import 'dart:typed_data'; 2 | import 'package:dart_mavlink/mavlink_dialect.dart'; 3 | import 'package:dart_mavlink/mavlink_message.dart'; 4 | import 'package:dart_mavlink/types.dart'; 5 | 6 | /// 7 | /// ICAROUS_TRACK_BAND_TYPES 8 | typedef IcarousTrackBandTypes = int; 9 | 10 | /// 11 | /// ICAROUS_TRACK_BAND_TYPE_NONE 12 | const IcarousTrackBandTypes icarousTrackBandTypeNone = 0; 13 | 14 | /// 15 | /// ICAROUS_TRACK_BAND_TYPE_NEAR 16 | const IcarousTrackBandTypes icarousTrackBandTypeNear = 1; 17 | 18 | /// 19 | /// ICAROUS_TRACK_BAND_TYPE_RECOVERY 20 | const IcarousTrackBandTypes icarousTrackBandTypeRecovery = 2; 21 | 22 | /// 23 | /// ICAROUS_FMS_STATE 24 | typedef IcarousFmsState = int; 25 | 26 | /// 27 | /// ICAROUS_FMS_STATE_IDLE 28 | const IcarousFmsState icarousFmsStateIdle = 0; 29 | 30 | /// 31 | /// ICAROUS_FMS_STATE_TAKEOFF 32 | const IcarousFmsState icarousFmsStateTakeoff = 1; 33 | 34 | /// 35 | /// ICAROUS_FMS_STATE_CLIMB 36 | const IcarousFmsState icarousFmsStateClimb = 2; 37 | 38 | /// 39 | /// ICAROUS_FMS_STATE_CRUISE 40 | const IcarousFmsState icarousFmsStateCruise = 3; 41 | 42 | /// 43 | /// ICAROUS_FMS_STATE_APPROACH 44 | const IcarousFmsState icarousFmsStateApproach = 4; 45 | 46 | /// 47 | /// ICAROUS_FMS_STATE_LAND 48 | const IcarousFmsState icarousFmsStateLand = 5; 49 | 50 | /// ICAROUS heartbeat 51 | /// 52 | /// ICAROUS_HEARTBEAT 53 | class IcarousHeartbeat implements MavlinkMessage { 54 | static const int _mavlinkMessageId = 42000; 55 | 56 | static const int _mavlinkCrcExtra = 227; 57 | 58 | static const int mavlinkEncodedLength = 1; 59 | 60 | @override 61 | int get mavlinkMessageId => _mavlinkMessageId; 62 | 63 | @override 64 | int get mavlinkCrcExtra => _mavlinkCrcExtra; 65 | 66 | /// See the FMS_STATE enum. 67 | /// 68 | /// MAVLink type: uint8_t 69 | /// 70 | /// enum: [IcarousFmsState] 71 | /// 72 | /// status 73 | final IcarousFmsState status; 74 | 75 | IcarousHeartbeat({ 76 | required this.status, 77 | }); 78 | 79 | IcarousHeartbeat copyWith({ 80 | IcarousFmsState? status, 81 | }) { 82 | return IcarousHeartbeat( 83 | status: status ?? this.status, 84 | ); 85 | } 86 | 87 | factory IcarousHeartbeat.parse(ByteData data_) { 88 | if (data_.lengthInBytes < IcarousHeartbeat.mavlinkEncodedLength) { 89 | var len = IcarousHeartbeat.mavlinkEncodedLength - data_.lengthInBytes; 90 | var d = data_.buffer.asUint8List().sublist(0, data_.lengthInBytes) + 91 | List.filled(len, 0); 92 | data_ = Uint8List.fromList(d).buffer.asByteData(); 93 | } 94 | var status = data_.getUint8(0); 95 | 96 | return IcarousHeartbeat(status: status); 97 | } 98 | 99 | @override 100 | ByteData serialize() { 101 | var data_ = ByteData(mavlinkEncodedLength); 102 | data_.setUint8(0, status); 103 | return data_; 104 | } 105 | } 106 | 107 | /// Kinematic multi bands (track) output from Daidalus 108 | /// 109 | /// ICAROUS_KINEMATIC_BANDS 110 | class IcarousKinematicBands implements MavlinkMessage { 111 | static const int _mavlinkMessageId = 42001; 112 | 113 | static const int _mavlinkCrcExtra = 239; 114 | 115 | static const int mavlinkEncodedLength = 46; 116 | 117 | @override 118 | int get mavlinkMessageId => _mavlinkMessageId; 119 | 120 | @override 121 | int get mavlinkCrcExtra => _mavlinkCrcExtra; 122 | 123 | /// min angle (degrees) 124 | /// 125 | /// MAVLink type: float 126 | /// 127 | /// units: deg 128 | /// 129 | /// min1 130 | final float min1; 131 | 132 | /// max angle (degrees) 133 | /// 134 | /// MAVLink type: float 135 | /// 136 | /// units: deg 137 | /// 138 | /// max1 139 | final float max1; 140 | 141 | /// min angle (degrees) 142 | /// 143 | /// MAVLink type: float 144 | /// 145 | /// units: deg 146 | /// 147 | /// min2 148 | final float min2; 149 | 150 | /// max angle (degrees) 151 | /// 152 | /// MAVLink type: float 153 | /// 154 | /// units: deg 155 | /// 156 | /// max2 157 | final float max2; 158 | 159 | /// min angle (degrees) 160 | /// 161 | /// MAVLink type: float 162 | /// 163 | /// units: deg 164 | /// 165 | /// min3 166 | final float min3; 167 | 168 | /// max angle (degrees) 169 | /// 170 | /// MAVLink type: float 171 | /// 172 | /// units: deg 173 | /// 174 | /// max3 175 | final float max3; 176 | 177 | /// min angle (degrees) 178 | /// 179 | /// MAVLink type: float 180 | /// 181 | /// units: deg 182 | /// 183 | /// min4 184 | final float min4; 185 | 186 | /// max angle (degrees) 187 | /// 188 | /// MAVLink type: float 189 | /// 190 | /// units: deg 191 | /// 192 | /// max4 193 | final float max4; 194 | 195 | /// min angle (degrees) 196 | /// 197 | /// MAVLink type: float 198 | /// 199 | /// units: deg 200 | /// 201 | /// min5 202 | final float min5; 203 | 204 | /// max angle (degrees) 205 | /// 206 | /// MAVLink type: float 207 | /// 208 | /// units: deg 209 | /// 210 | /// max5 211 | final float max5; 212 | 213 | /// Number of track bands 214 | /// 215 | /// MAVLink type: int8_t 216 | /// 217 | /// numBands 218 | final int8_t numbands; 219 | 220 | /// See the TRACK_BAND_TYPES enum. 221 | /// 222 | /// MAVLink type: uint8_t 223 | /// 224 | /// enum: [IcarousTrackBandTypes] 225 | /// 226 | /// type1 227 | final IcarousTrackBandTypes type1; 228 | 229 | /// See the TRACK_BAND_TYPES enum. 230 | /// 231 | /// MAVLink type: uint8_t 232 | /// 233 | /// enum: [IcarousTrackBandTypes] 234 | /// 235 | /// type2 236 | final IcarousTrackBandTypes type2; 237 | 238 | /// See the TRACK_BAND_TYPES enum. 239 | /// 240 | /// MAVLink type: uint8_t 241 | /// 242 | /// enum: [IcarousTrackBandTypes] 243 | /// 244 | /// type3 245 | final IcarousTrackBandTypes type3; 246 | 247 | /// See the TRACK_BAND_TYPES enum. 248 | /// 249 | /// MAVLink type: uint8_t 250 | /// 251 | /// enum: [IcarousTrackBandTypes] 252 | /// 253 | /// type4 254 | final IcarousTrackBandTypes type4; 255 | 256 | /// See the TRACK_BAND_TYPES enum. 257 | /// 258 | /// MAVLink type: uint8_t 259 | /// 260 | /// enum: [IcarousTrackBandTypes] 261 | /// 262 | /// type5 263 | final IcarousTrackBandTypes type5; 264 | 265 | IcarousKinematicBands({ 266 | required this.min1, 267 | required this.max1, 268 | required this.min2, 269 | required this.max2, 270 | required this.min3, 271 | required this.max3, 272 | required this.min4, 273 | required this.max4, 274 | required this.min5, 275 | required this.max5, 276 | required this.numbands, 277 | required this.type1, 278 | required this.type2, 279 | required this.type3, 280 | required this.type4, 281 | required this.type5, 282 | }); 283 | 284 | IcarousKinematicBands copyWith({ 285 | float? min1, 286 | float? max1, 287 | float? min2, 288 | float? max2, 289 | float? min3, 290 | float? max3, 291 | float? min4, 292 | float? max4, 293 | float? min5, 294 | float? max5, 295 | int8_t? numbands, 296 | IcarousTrackBandTypes? type1, 297 | IcarousTrackBandTypes? type2, 298 | IcarousTrackBandTypes? type3, 299 | IcarousTrackBandTypes? type4, 300 | IcarousTrackBandTypes? type5, 301 | }) { 302 | return IcarousKinematicBands( 303 | min1: min1 ?? this.min1, 304 | max1: max1 ?? this.max1, 305 | min2: min2 ?? this.min2, 306 | max2: max2 ?? this.max2, 307 | min3: min3 ?? this.min3, 308 | max3: max3 ?? this.max3, 309 | min4: min4 ?? this.min4, 310 | max4: max4 ?? this.max4, 311 | min5: min5 ?? this.min5, 312 | max5: max5 ?? this.max5, 313 | numbands: numbands ?? this.numbands, 314 | type1: type1 ?? this.type1, 315 | type2: type2 ?? this.type2, 316 | type3: type3 ?? this.type3, 317 | type4: type4 ?? this.type4, 318 | type5: type5 ?? this.type5, 319 | ); 320 | } 321 | 322 | factory IcarousKinematicBands.parse(ByteData data_) { 323 | if (data_.lengthInBytes < IcarousKinematicBands.mavlinkEncodedLength) { 324 | var len = 325 | IcarousKinematicBands.mavlinkEncodedLength - data_.lengthInBytes; 326 | var d = data_.buffer.asUint8List().sublist(0, data_.lengthInBytes) + 327 | List.filled(len, 0); 328 | data_ = Uint8List.fromList(d).buffer.asByteData(); 329 | } 330 | var min1 = data_.getFloat32(0, Endian.little); 331 | var max1 = data_.getFloat32(4, Endian.little); 332 | var min2 = data_.getFloat32(8, Endian.little); 333 | var max2 = data_.getFloat32(12, Endian.little); 334 | var min3 = data_.getFloat32(16, Endian.little); 335 | var max3 = data_.getFloat32(20, Endian.little); 336 | var min4 = data_.getFloat32(24, Endian.little); 337 | var max4 = data_.getFloat32(28, Endian.little); 338 | var min5 = data_.getFloat32(32, Endian.little); 339 | var max5 = data_.getFloat32(36, Endian.little); 340 | var numbands = data_.getInt8(40); 341 | var type1 = data_.getUint8(41); 342 | var type2 = data_.getUint8(42); 343 | var type3 = data_.getUint8(43); 344 | var type4 = data_.getUint8(44); 345 | var type5 = data_.getUint8(45); 346 | 347 | return IcarousKinematicBands( 348 | min1: min1, 349 | max1: max1, 350 | min2: min2, 351 | max2: max2, 352 | min3: min3, 353 | max3: max3, 354 | min4: min4, 355 | max4: max4, 356 | min5: min5, 357 | max5: max5, 358 | numbands: numbands, 359 | type1: type1, 360 | type2: type2, 361 | type3: type3, 362 | type4: type4, 363 | type5: type5); 364 | } 365 | 366 | @override 367 | ByteData serialize() { 368 | var data_ = ByteData(mavlinkEncodedLength); 369 | data_.setFloat32(0, min1, Endian.little); 370 | data_.setFloat32(4, max1, Endian.little); 371 | data_.setFloat32(8, min2, Endian.little); 372 | data_.setFloat32(12, max2, Endian.little); 373 | data_.setFloat32(16, min3, Endian.little); 374 | data_.setFloat32(20, max3, Endian.little); 375 | data_.setFloat32(24, min4, Endian.little); 376 | data_.setFloat32(28, max4, Endian.little); 377 | data_.setFloat32(32, min5, Endian.little); 378 | data_.setFloat32(36, max5, Endian.little); 379 | data_.setInt8(40, numbands); 380 | data_.setUint8(41, type1); 381 | data_.setUint8(42, type2); 382 | data_.setUint8(43, type3); 383 | data_.setUint8(44, type4); 384 | data_.setUint8(45, type5); 385 | return data_; 386 | } 387 | } 388 | 389 | class MavlinkDialectIcarous implements MavlinkDialect { 390 | static const int mavlinkVersion = 0; 391 | 392 | @override 393 | int get version => mavlinkVersion; 394 | 395 | @override 396 | MavlinkMessage? parse(int messageID, ByteData data) { 397 | switch (messageID) { 398 | case 42000: 399 | return IcarousHeartbeat.parse(data); 400 | case 42001: 401 | return IcarousKinematicBands.parse(data); 402 | default: 403 | return null; 404 | } 405 | } 406 | 407 | @override 408 | int crcExtra(int messageID) { 409 | switch (messageID) { 410 | case 42000: 411 | return IcarousHeartbeat._mavlinkCrcExtra; 412 | case 42001: 413 | return IcarousKinematicBands._mavlinkCrcExtra; 414 | default: 415 | return -1; 416 | } 417 | } 418 | } 419 | -------------------------------------------------------------------------------- /lib/dialects/csairlink.dart: -------------------------------------------------------------------------------- 1 | import 'dart:typed_data'; 2 | import 'package:dart_mavlink/mavlink_dialect.dart'; 3 | import 'package:dart_mavlink/mavlink_message.dart'; 4 | import 'package:dart_mavlink/types.dart'; 5 | 6 | /// 7 | /// AIRLINK_AUTH_RESPONSE_TYPE 8 | typedef AirlinkAuthResponseType = int; 9 | 10 | /// Login or password error 11 | /// 12 | /// AIRLINK_ERROR_LOGIN_OR_PASS 13 | const AirlinkAuthResponseType airlinkErrorLoginOrPass = 0; 14 | 15 | /// Auth successful 16 | /// 17 | /// AIRLINK_AUTH_OK 18 | const AirlinkAuthResponseType airlinkAuthOk = 1; 19 | 20 | /// 21 | /// AIRLINK_EYE_GS_HOLE_PUSH_RESP_TYPE 22 | typedef AirlinkEyeGsHolePushRespType = int; 23 | 24 | /// 25 | /// AIRLINK_HPR_PARTNER_NOT_READY 26 | const AirlinkEyeGsHolePushRespType airlinkHprPartnerNotReady = 0; 27 | 28 | /// 29 | /// AIRLINK_HPR_PARTNER_READY 30 | const AirlinkEyeGsHolePushRespType airlinkHprPartnerReady = 1; 31 | 32 | /// 33 | /// AIRLINK_EYE_IP_VERSION 34 | typedef AirlinkEyeIpVersion = int; 35 | 36 | /// 37 | /// AIRLINK_IP_V4 38 | const AirlinkEyeIpVersion airlinkIpV4 = 0; 39 | 40 | /// 41 | /// AIRLINK_IP_V6 42 | const AirlinkEyeIpVersion airlinkIpV6 = 1; 43 | 44 | /// 45 | /// AIRLINK_EYE_HOLE_PUSH_TYPE 46 | typedef AirlinkEyeHolePushType = int; 47 | 48 | /// 49 | /// AIRLINK_HP_NOT_PENETRATED 50 | const AirlinkEyeHolePushType airlinkHpNotPenetrated = 0; 51 | 52 | /// 53 | /// AIRLINK_HP_BROKEN 54 | const AirlinkEyeHolePushType airlinkHpBroken = 1; 55 | 56 | /// 57 | /// AIRLINK_EYE_TURN_INIT_TYPE 58 | typedef AirlinkEyeTurnInitType = int; 59 | 60 | /// 61 | /// AIRLINK_TURN_INIT_START 62 | const AirlinkEyeTurnInitType airlinkTurnInitStart = 0; 63 | 64 | /// 65 | /// AIRLINK_TURN_INIT_OK 66 | const AirlinkEyeTurnInitType airlinkTurnInitOk = 1; 67 | 68 | /// 69 | /// AIRLINK_TURN_INIT_BAD 70 | const AirlinkEyeTurnInitType airlinkTurnInitBad = 2; 71 | 72 | /// Authorization package 73 | /// 74 | /// AIRLINK_AUTH 75 | class AirlinkAuth implements MavlinkMessage { 76 | static const int _mavlinkMessageId = 52000; 77 | 78 | static const int _mavlinkCrcExtra = 13; 79 | 80 | static const int mavlinkEncodedLength = 100; 81 | 82 | @override 83 | int get mavlinkMessageId => _mavlinkMessageId; 84 | 85 | @override 86 | int get mavlinkCrcExtra => _mavlinkCrcExtra; 87 | 88 | /// Login 89 | /// 90 | /// MAVLink type: char[50] 91 | /// 92 | /// login 93 | final List login; 94 | 95 | /// Password 96 | /// 97 | /// MAVLink type: char[50] 98 | /// 99 | /// password 100 | final List password; 101 | 102 | AirlinkAuth({ 103 | required this.login, 104 | required this.password, 105 | }); 106 | 107 | AirlinkAuth copyWith({ 108 | List? login, 109 | List? password, 110 | }) { 111 | return AirlinkAuth( 112 | login: login ?? this.login, 113 | password: password ?? this.password, 114 | ); 115 | } 116 | 117 | factory AirlinkAuth.parse(ByteData data_) { 118 | if (data_.lengthInBytes < AirlinkAuth.mavlinkEncodedLength) { 119 | var len = AirlinkAuth.mavlinkEncodedLength - data_.lengthInBytes; 120 | var d = data_.buffer.asUint8List().sublist(0, data_.lengthInBytes) + 121 | List.filled(len, 0); 122 | data_ = Uint8List.fromList(d).buffer.asByteData(); 123 | } 124 | var login = MavlinkMessage.asInt8List(data_, 0, 50); 125 | var password = MavlinkMessage.asInt8List(data_, 50, 50); 126 | 127 | return AirlinkAuth(login: login, password: password); 128 | } 129 | 130 | @override 131 | ByteData serialize() { 132 | var data_ = ByteData(mavlinkEncodedLength); 133 | MavlinkMessage.setInt8List(data_, 0, login); 134 | MavlinkMessage.setInt8List(data_, 50, password); 135 | return data_; 136 | } 137 | } 138 | 139 | /// Response to the authorization request 140 | /// 141 | /// AIRLINK_AUTH_RESPONSE 142 | class AirlinkAuthResponse implements MavlinkMessage { 143 | static const int _mavlinkMessageId = 52001; 144 | 145 | static const int _mavlinkCrcExtra = 239; 146 | 147 | static const int mavlinkEncodedLength = 1; 148 | 149 | @override 150 | int get mavlinkMessageId => _mavlinkMessageId; 151 | 152 | @override 153 | int get mavlinkCrcExtra => _mavlinkCrcExtra; 154 | 155 | /// Response type 156 | /// 157 | /// MAVLink type: uint8_t 158 | /// 159 | /// enum: [AirlinkAuthResponseType] 160 | /// 161 | /// resp_type 162 | final AirlinkAuthResponseType respType; 163 | 164 | AirlinkAuthResponse({ 165 | required this.respType, 166 | }); 167 | 168 | AirlinkAuthResponse copyWith({ 169 | AirlinkAuthResponseType? respType, 170 | }) { 171 | return AirlinkAuthResponse( 172 | respType: respType ?? this.respType, 173 | ); 174 | } 175 | 176 | factory AirlinkAuthResponse.parse(ByteData data_) { 177 | if (data_.lengthInBytes < AirlinkAuthResponse.mavlinkEncodedLength) { 178 | var len = AirlinkAuthResponse.mavlinkEncodedLength - data_.lengthInBytes; 179 | var d = data_.buffer.asUint8List().sublist(0, data_.lengthInBytes) + 180 | List.filled(len, 0); 181 | data_ = Uint8List.fromList(d).buffer.asByteData(); 182 | } 183 | var respType = data_.getUint8(0); 184 | 185 | return AirlinkAuthResponse(respType: respType); 186 | } 187 | 188 | @override 189 | ByteData serialize() { 190 | var data_ = ByteData(mavlinkEncodedLength); 191 | data_.setUint8(0, respType); 192 | return data_; 193 | } 194 | } 195 | 196 | /// Request to hole punching 197 | /// 198 | /// AIRLINK_EYE_GS_HOLE_PUSH_REQUEST 199 | class AirlinkEyeGsHolePushRequest implements MavlinkMessage { 200 | static const int _mavlinkMessageId = 52002; 201 | 202 | static const int _mavlinkCrcExtra = 24; 203 | 204 | static const int mavlinkEncodedLength = 1; 205 | 206 | @override 207 | int get mavlinkMessageId => _mavlinkMessageId; 208 | 209 | @override 210 | int get mavlinkCrcExtra => _mavlinkCrcExtra; 211 | 212 | /// Hole push response type 213 | /// 214 | /// MAVLink type: uint8_t 215 | /// 216 | /// enum: [AirlinkEyeGsHolePushRespType] 217 | /// 218 | /// resp_type 219 | final AirlinkEyeGsHolePushRespType respType; 220 | 221 | AirlinkEyeGsHolePushRequest({ 222 | required this.respType, 223 | }); 224 | 225 | AirlinkEyeGsHolePushRequest copyWith({ 226 | AirlinkEyeGsHolePushRespType? respType, 227 | }) { 228 | return AirlinkEyeGsHolePushRequest( 229 | respType: respType ?? this.respType, 230 | ); 231 | } 232 | 233 | factory AirlinkEyeGsHolePushRequest.parse(ByteData data_) { 234 | if (data_.lengthInBytes < 235 | AirlinkEyeGsHolePushRequest.mavlinkEncodedLength) { 236 | var len = AirlinkEyeGsHolePushRequest.mavlinkEncodedLength - 237 | data_.lengthInBytes; 238 | var d = data_.buffer.asUint8List().sublist(0, data_.lengthInBytes) + 239 | List.filled(len, 0); 240 | data_ = Uint8List.fromList(d).buffer.asByteData(); 241 | } 242 | var respType = data_.getUint8(0); 243 | 244 | return AirlinkEyeGsHolePushRequest(respType: respType); 245 | } 246 | 247 | @override 248 | ByteData serialize() { 249 | var data_ = ByteData(mavlinkEncodedLength); 250 | data_.setUint8(0, respType); 251 | return data_; 252 | } 253 | } 254 | 255 | /// Response information about the connected device 256 | /// 257 | /// AIRLINK_EYE_GS_HOLE_PUSH_RESPONSE 258 | class AirlinkEyeGsHolePushResponse implements MavlinkMessage { 259 | static const int _mavlinkMessageId = 52003; 260 | 261 | static const int _mavlinkCrcExtra = 166; 262 | 263 | static const int mavlinkEncodedLength = 26; 264 | 265 | @override 266 | int get mavlinkMessageId => _mavlinkMessageId; 267 | 268 | @override 269 | int get mavlinkCrcExtra => _mavlinkCrcExtra; 270 | 271 | /// port 272 | /// 273 | /// MAVLink type: uint32_t 274 | /// 275 | /// ip_port 276 | final uint32_t ipPort; 277 | 278 | /// Hole push response type 279 | /// 280 | /// MAVLink type: uint8_t 281 | /// 282 | /// enum: [AirlinkEyeGsHolePushRespType] 283 | /// 284 | /// resp_type 285 | final AirlinkEyeGsHolePushRespType respType; 286 | 287 | /// ip version 288 | /// 289 | /// MAVLink type: uint8_t 290 | /// 291 | /// enum: [AirlinkEyeIpVersion] 292 | /// 293 | /// ip_version 294 | final AirlinkEyeIpVersion ipVersion; 295 | 296 | /// ip 4 address 297 | /// 298 | /// MAVLink type: uint8_t[4] 299 | /// 300 | /// ip_address_4 301 | final List ipAddress4; 302 | 303 | /// ip 6 address 304 | /// 305 | /// MAVLink type: uint8_t[16] 306 | /// 307 | /// ip_address_6 308 | final List ipAddress6; 309 | 310 | AirlinkEyeGsHolePushResponse({ 311 | required this.ipPort, 312 | required this.respType, 313 | required this.ipVersion, 314 | required this.ipAddress4, 315 | required this.ipAddress6, 316 | }); 317 | 318 | AirlinkEyeGsHolePushResponse copyWith({ 319 | uint32_t? ipPort, 320 | AirlinkEyeGsHolePushRespType? respType, 321 | AirlinkEyeIpVersion? ipVersion, 322 | List? ipAddress4, 323 | List? ipAddress6, 324 | }) { 325 | return AirlinkEyeGsHolePushResponse( 326 | ipPort: ipPort ?? this.ipPort, 327 | respType: respType ?? this.respType, 328 | ipVersion: ipVersion ?? this.ipVersion, 329 | ipAddress4: ipAddress4 ?? this.ipAddress4, 330 | ipAddress6: ipAddress6 ?? this.ipAddress6, 331 | ); 332 | } 333 | 334 | factory AirlinkEyeGsHolePushResponse.parse(ByteData data_) { 335 | if (data_.lengthInBytes < 336 | AirlinkEyeGsHolePushResponse.mavlinkEncodedLength) { 337 | var len = AirlinkEyeGsHolePushResponse.mavlinkEncodedLength - 338 | data_.lengthInBytes; 339 | var d = data_.buffer.asUint8List().sublist(0, data_.lengthInBytes) + 340 | List.filled(len, 0); 341 | data_ = Uint8List.fromList(d).buffer.asByteData(); 342 | } 343 | var ipPort = data_.getUint32(0, Endian.little); 344 | var respType = data_.getUint8(4); 345 | var ipVersion = data_.getUint8(5); 346 | var ipAddress4 = MavlinkMessage.asUint8List(data_, 6, 4); 347 | var ipAddress6 = MavlinkMessage.asUint8List(data_, 10, 16); 348 | 349 | return AirlinkEyeGsHolePushResponse( 350 | ipPort: ipPort, 351 | respType: respType, 352 | ipVersion: ipVersion, 353 | ipAddress4: ipAddress4, 354 | ipAddress6: ipAddress6); 355 | } 356 | 357 | @override 358 | ByteData serialize() { 359 | var data_ = ByteData(mavlinkEncodedLength); 360 | data_.setUint32(0, ipPort, Endian.little); 361 | data_.setUint8(4, respType); 362 | data_.setUint8(5, ipVersion); 363 | MavlinkMessage.setUint8List(data_, 6, ipAddress4); 364 | MavlinkMessage.setUint8List(data_, 10, ipAddress6); 365 | return data_; 366 | } 367 | } 368 | 369 | /// A package with information about the hole punching status. It is used for constant sending to avoid NAT closing timeout. 370 | /// 371 | /// AIRLINK_EYE_HP 372 | class AirlinkEyeHp implements MavlinkMessage { 373 | static const int _mavlinkMessageId = 52004; 374 | 375 | static const int _mavlinkCrcExtra = 39; 376 | 377 | static const int mavlinkEncodedLength = 1; 378 | 379 | @override 380 | int get mavlinkMessageId => _mavlinkMessageId; 381 | 382 | @override 383 | int get mavlinkCrcExtra => _mavlinkCrcExtra; 384 | 385 | /// Hole push response type 386 | /// 387 | /// MAVLink type: uint8_t 388 | /// 389 | /// enum: [AirlinkEyeHolePushType] 390 | /// 391 | /// resp_type 392 | final AirlinkEyeHolePushType respType; 393 | 394 | AirlinkEyeHp({ 395 | required this.respType, 396 | }); 397 | 398 | AirlinkEyeHp copyWith({ 399 | AirlinkEyeHolePushType? respType, 400 | }) { 401 | return AirlinkEyeHp( 402 | respType: respType ?? this.respType, 403 | ); 404 | } 405 | 406 | factory AirlinkEyeHp.parse(ByteData data_) { 407 | if (data_.lengthInBytes < AirlinkEyeHp.mavlinkEncodedLength) { 408 | var len = AirlinkEyeHp.mavlinkEncodedLength - data_.lengthInBytes; 409 | var d = data_.buffer.asUint8List().sublist(0, data_.lengthInBytes) + 410 | List.filled(len, 0); 411 | data_ = Uint8List.fromList(d).buffer.asByteData(); 412 | } 413 | var respType = data_.getUint8(0); 414 | 415 | return AirlinkEyeHp(respType: respType); 416 | } 417 | 418 | @override 419 | ByteData serialize() { 420 | var data_ = ByteData(mavlinkEncodedLength); 421 | data_.setUint8(0, respType); 422 | return data_; 423 | } 424 | } 425 | 426 | /// Initializing the TURN protocol 427 | /// 428 | /// AIRLINK_EYE_TURN_INIT 429 | class AirlinkEyeTurnInit implements MavlinkMessage { 430 | static const int _mavlinkMessageId = 52005; 431 | 432 | static const int _mavlinkCrcExtra = 145; 433 | 434 | static const int mavlinkEncodedLength = 1; 435 | 436 | @override 437 | int get mavlinkMessageId => _mavlinkMessageId; 438 | 439 | @override 440 | int get mavlinkCrcExtra => _mavlinkCrcExtra; 441 | 442 | /// Turn init type 443 | /// 444 | /// MAVLink type: uint8_t 445 | /// 446 | /// enum: [AirlinkEyeTurnInitType] 447 | /// 448 | /// resp_type 449 | final AirlinkEyeTurnInitType respType; 450 | 451 | AirlinkEyeTurnInit({ 452 | required this.respType, 453 | }); 454 | 455 | AirlinkEyeTurnInit copyWith({ 456 | AirlinkEyeTurnInitType? respType, 457 | }) { 458 | return AirlinkEyeTurnInit( 459 | respType: respType ?? this.respType, 460 | ); 461 | } 462 | 463 | factory AirlinkEyeTurnInit.parse(ByteData data_) { 464 | if (data_.lengthInBytes < AirlinkEyeTurnInit.mavlinkEncodedLength) { 465 | var len = AirlinkEyeTurnInit.mavlinkEncodedLength - data_.lengthInBytes; 466 | var d = data_.buffer.asUint8List().sublist(0, data_.lengthInBytes) + 467 | List.filled(len, 0); 468 | data_ = Uint8List.fromList(d).buffer.asByteData(); 469 | } 470 | var respType = data_.getUint8(0); 471 | 472 | return AirlinkEyeTurnInit(respType: respType); 473 | } 474 | 475 | @override 476 | ByteData serialize() { 477 | var data_ = ByteData(mavlinkEncodedLength); 478 | data_.setUint8(0, respType); 479 | return data_; 480 | } 481 | } 482 | 483 | class MavlinkDialectCsairlink implements MavlinkDialect { 484 | static const int mavlinkVersion = 3; 485 | 486 | @override 487 | int get version => mavlinkVersion; 488 | 489 | @override 490 | MavlinkMessage? parse(int messageID, ByteData data) { 491 | switch (messageID) { 492 | case 52000: 493 | return AirlinkAuth.parse(data); 494 | case 52001: 495 | return AirlinkAuthResponse.parse(data); 496 | case 52002: 497 | return AirlinkEyeGsHolePushRequest.parse(data); 498 | case 52003: 499 | return AirlinkEyeGsHolePushResponse.parse(data); 500 | case 52004: 501 | return AirlinkEyeHp.parse(data); 502 | case 52005: 503 | return AirlinkEyeTurnInit.parse(data); 504 | default: 505 | return null; 506 | } 507 | } 508 | 509 | @override 510 | int crcExtra(int messageID) { 511 | switch (messageID) { 512 | case 52000: 513 | return AirlinkAuth._mavlinkCrcExtra; 514 | case 52001: 515 | return AirlinkAuthResponse._mavlinkCrcExtra; 516 | case 52002: 517 | return AirlinkEyeGsHolePushRequest._mavlinkCrcExtra; 518 | case 52003: 519 | return AirlinkEyeGsHolePushResponse._mavlinkCrcExtra; 520 | case 52004: 521 | return AirlinkEyeHp._mavlinkCrcExtra; 522 | case 52005: 523 | return AirlinkEyeTurnInit._mavlinkCrcExtra; 524 | default: 525 | return -1; 526 | } 527 | } 528 | } 529 | -------------------------------------------------------------------------------- /tool/generate.dart: -------------------------------------------------------------------------------- 1 | import 'dart:io'; 2 | import 'dart:collection'; 3 | import 'dart:math'; 4 | import 'package:xml/xml.dart'; 5 | import 'package:path/path.dart' as path; 6 | import 'package:dart_mavlink/crc.dart'; 7 | 8 | class DialectEnums extends IterableMixin { 9 | final List _enums; 10 | 11 | DialectEnums(this._enums); 12 | 13 | @override 14 | Iterator get iterator => _enums.iterator; 15 | 16 | @override 17 | int get length => _enums.length; 18 | 19 | void addAll(DialectEnums iterable) { 20 | for (var e in iterable) { 21 | if (_hasName(e.name)) { 22 | continue; 23 | } 24 | 25 | _enums.add(e); 26 | } 27 | } 28 | 29 | bool _hasName(String name) { 30 | for (var e in _enums) { 31 | if (e.name == name) { 32 | return true; 33 | } 34 | } 35 | return false; 36 | } 37 | 38 | static DialectEnums parseElement(XmlElement? elmEnums) { 39 | if (elmEnums == null) { 40 | return DialectEnums([]); 41 | } 42 | 43 | List enums = []; 44 | for (var elmEnum in elmEnums.findAllElements('enum')) { 45 | String name = elmEnum.getAttribute('name') ?? ''; 46 | if (name.isEmpty) { 47 | throw FormatException('The name of enum element should not be empty.'); 48 | } 49 | 50 | var description = elmEnum.getElement('description')?.text; 51 | 52 | DialectDeprecated? dlctDeprecated = DialectDeprecated.parseElement(elmEnum.getElement('deprecated')); 53 | 54 | List? entries; 55 | for (var elmEntry in elmEnum.findAllElements('entry')) { 56 | entries ??= []; 57 | 58 | bool enumIsMavCmd = (name == 'MAV_CMD'); 59 | var dlctEntry = DialectEntry.parseElement(elmEntry, enumIsMavCmd); 60 | 61 | entries.add(dlctEntry); 62 | } 63 | 64 | enums.add(DialectEnum(name, description, dlctDeprecated, entries)); 65 | } 66 | 67 | return DialectEnums(enums); 68 | } 69 | } 70 | 71 | /// Contains [](https://mavlink.io/en/guide/xml_schema.html#enum) 72 | class DialectEnum { 73 | /// Mandatory. 74 | final String name; 75 | 76 | /// Optional. 77 | final String? description; 78 | 79 | /// Optional 80 | final DialectDeprecated? deprecated; 81 | 82 | /// Optional 83 | final List? entries; 84 | 85 | final String nameForDart; 86 | 87 | DialectEnum(this.name, this.description, this.deprecated, this.entries) 88 | : nameForDart = camelCase(name); 89 | } 90 | 91 | /// Containes [enum](https://mavlink.io/en/guide/xml_schema.html#entry) 92 | class DialectEntry { 93 | /// Mandatory. 94 | final String name; 95 | 96 | /// Optional. 97 | final int? value; 98 | 99 | /// Optional. 100 | final String? description; 101 | 102 | /// Optional. 103 | final DialectDeprecated? deprecated; 104 | 105 | /// Optional. 106 | final bool wip; 107 | 108 | /// Optional. for MAV_CMD. Default value is true. 109 | final bool? hasLocation; 110 | 111 | /// Optional. for MAV_CMD. Default value is true. 112 | final bool? isDestination; 113 | 114 | /// Optional. for MAV_CMD. 115 | final List? params; 116 | 117 | final String nameForDart; 118 | 119 | DialectEntry(this.name, this.value, this.description, this.deprecated, this.wip, this.hasLocation, this.isDestination, this.params) 120 | : nameForDart = lowerCamelCase(name); 121 | 122 | static DialectEntry parseElement(XmlElement elmEntry, bool enumIsMavCmd) { 123 | String name = elmEntry.getAttribute('name') ?? ''; 124 | if (name.isEmpty) { 125 | throw FormatException('The name of deprecated element should not be empty.'); 126 | } 127 | 128 | int value; 129 | var valueStr = (elmEntry.getAttribute('value') ?? ''); 130 | 131 | // Values in the xml schema can be one of 4 types: bare int (eg; 8), 2 raised to some power (eg; 2**4), hex (eg; 0xFE), or binary, (eg; 0b001000) 132 | // Dart handles the raw int and the hex natively with the int.parse() function, so we have to test for the other cases. 133 | if (valueStr.startsWith("2**")) { 134 | var exponent = int.parse(valueStr.split("2**")[1]); 135 | value = pow(2, exponent).toInt(); 136 | } else if (valueStr.startsWith("0b")) { 137 | var bitString = valueStr.split("0b")[1]; 138 | value = int.parse(bitString, radix: 2); 139 | } else { 140 | value = int.parse(valueStr); 141 | } 142 | String? description = elmEntry.getElement('description')?.text; 143 | 144 | var deprecated = DialectDeprecated.parseElement(elmEntry.getElement('deprecated')); 145 | 146 | var wip = (elmEntry.getElement('wip') == null) ? false : true; 147 | 148 | var attrHasLocation = elmEntry.getAttribute('hasLocation'); 149 | var attrIsDestination = elmEntry.getAttribute('isDestination'); 150 | 151 | bool? hasLocation; 152 | bool? isDestination; 153 | List? params; 154 | if (enumIsMavCmd) { 155 | hasLocation = _castAsBool(attrHasLocation, true); 156 | isDestination = _castAsBool(attrIsDestination, true); 157 | 158 | var elmParams = elmEntry.findAllElements('param'); 159 | params = List.generate(7, (index) => DialectParam.empty(index + 1)); 160 | 161 | for (int i = 0; i < elmParams.length; i++) { 162 | var elmParam = elmParams.elementAt(i); 163 | 164 | var index = int.parse(elmParam.getAttribute('index') ?? ''); 165 | 166 | var description = elmParam.text; 167 | 168 | params[index - 1] = DialectParam( 169 | index, 170 | description, 171 | elmParam.getAttribute('label'), 172 | elmParam.getAttribute('units'), 173 | elmParam.getAttribute('enum'), 174 | elmParam.getAttribute('decimalPlaces'), 175 | elmParam.getAttribute('increment'), 176 | elmParam.getAttribute('minValue'), 177 | elmParam.getAttribute('maxValue'), 178 | _castAsBool(elmParam.getAttribute('reserved'), false) 179 | ); 180 | } 181 | } else { 182 | if (attrHasLocation != null || attrIsDestination != null) { 183 | throw FormatException('The hasLocation attribute and isDestination must be child of MAV_CMD.'); 184 | } 185 | } 186 | 187 | 188 | return DialectEntry(name, value, description, deprecated, wip, hasLocation, isDestination, params); 189 | } 190 | 191 | static bool _castAsBool(String? str, bool defaultValue) { 192 | if (str == null) { 193 | return defaultValue; 194 | } 195 | switch (str) { 196 | case 'true': 197 | return true; 198 | case 'false': 199 | return false; 200 | default: 201 | throw FormatException('The hasLocation of etnry element should not be true or false but "$str"'); 202 | } 203 | } 204 | } 205 | 206 | class DialectParam { 207 | /// Mandatory. 208 | final int index; 209 | 210 | /// Mandatory. 211 | final String description; 212 | 213 | /// Optional. 214 | final String? label; 215 | 216 | /// Optional. 217 | final String? units; 218 | 219 | /// Optional. 220 | final String? enum_; 221 | 222 | /// Optional. 223 | final String? decimalPlaces; 224 | 225 | /// Optional. 226 | final String? increment; 227 | 228 | /// Optional. 229 | final String? minValue; 230 | 231 | /// Optional. 232 | final String? maxValue; 233 | 234 | // Optional. Default is false. 235 | final bool? reserved; 236 | 237 | DialectParam.empty(this.index) : 238 | description ="", 239 | label = null, 240 | units = null, 241 | enum_ = null, 242 | decimalPlaces = null, 243 | increment = null, 244 | minValue = null, 245 | maxValue = null, 246 | reserved = null; 247 | 248 | DialectParam(this.index, this.description, this.label, this.units, this.enum_, this.decimalPlaces, this.increment, this.minValue, this.maxValue, this.reserved); 249 | } 250 | 251 | class DialectDeprecated { 252 | /// Mandatory. 253 | final String since; 254 | 255 | /// Mandatory. It is possible to be empty string. 256 | final String replacedBy; 257 | 258 | /// Mandatory. It is possible to be empty string. 259 | final String text; 260 | 261 | DialectDeprecated(this.since, this.replacedBy, this.text); 262 | 263 | static DialectDeprecated? parseElement(XmlElement? elmDeprecated) { 264 | if (elmDeprecated == null) { 265 | return null; 266 | } 267 | 268 | String since = elmDeprecated.getAttribute('since') ?? ''; 269 | String replacedBy = elmDeprecated.getAttribute('replaced_by') ?? ''; 270 | String text = elmDeprecated.text; 271 | 272 | if (since.isEmpty) { 273 | throw FormatException('The since of deprecated element should not be empty.'); 274 | } 275 | 276 | return DialectDeprecated(since, replacedBy, text); 277 | } 278 | } 279 | 280 | class DialectMessages extends IterableMixin { 281 | final List _messages; 282 | 283 | DialectMessages(this._messages); 284 | 285 | @override 286 | Iterator get iterator => _messages.iterator; 287 | 288 | @override 289 | int get length => _messages.length; 290 | 291 | void addAll(DialectMessages iterable) { 292 | for (var m in iterable) { 293 | if (_hasID(m.id)) { 294 | continue; 295 | } 296 | 297 | _messages.add(m); 298 | } 299 | } 300 | 301 | bool _hasID(int id) { 302 | for (var m in _messages) { 303 | if (m.id == id) { 304 | return true; 305 | } 306 | } 307 | return false; 308 | } 309 | 310 | static DialectMessages parseElement(XmlElement? elmMessages) { 311 | if (elmMessages == null) { 312 | return DialectMessages([]); 313 | } 314 | 315 | List messages = []; 316 | 317 | for (var elmMessage in elmMessages.findAllElements('message')) { 318 | int id = int.parse(elmMessage.getAttribute('id') ?? '-1'); 319 | if (id == -1) { 320 | throw FormatException('The id of message element should not be emtpy.'); 321 | } 322 | 323 | String name = elmMessage.getAttribute('name') ?? ''; 324 | if (name.isEmpty) { 325 | throw FormatException('The name of message element should not be empty.'); 326 | } 327 | 328 | String? description = elmMessage.getElement('description')?.text; 329 | if (description == null) { 330 | throw FormatException('The description of message element should not be empty.'); 331 | } 332 | 333 | DialectDeprecated? dlctDeprecated = DialectDeprecated.parseElement(elmMessage.getElement('deprecated')); 334 | 335 | List fields = []; 336 | bool isExtenstion = false; 337 | for (var child in elmMessage.childElements) { 338 | String name = child.name.toString(); 339 | if (name == 'field') { 340 | fields.add(DialectField.parseElement(child, isExtenstion)); 341 | } else if (name == 'extensions') { 342 | isExtenstion = true; 343 | } 344 | } 345 | 346 | messages.add(DialectMessage(id, name, description, fields, dlctDeprecated)); 347 | } 348 | 349 | return DialectMessages(messages); 350 | } 351 | } 352 | 353 | class DialectMessage { 354 | final int id; 355 | final String name; 356 | final String description; 357 | final List fields; 358 | 359 | /// Optional 360 | final DialectDeprecated? deprecated; 361 | 362 | final String nameForDart; 363 | 364 | /// https://mavlink.io/en/guide/serialization.html#field_reordering 365 | final List orderedFields; 366 | 367 | DialectMessage(this.id, this.name, this.description, this.fields,this.deprecated) 368 | : nameForDart = camelCase(name) 369 | , orderedFields = fields.where((f) => !f.isExtension).toList() 370 | ..sort((a, b) => b.parsedType.bit.compareTo(a.parsedType.bit)) 371 | ..addAll(fields.where((f) => f.isExtension)); 372 | 373 | int calculateCrcExtra() { 374 | var crc = CrcX25(); 375 | crc.accumulateString(name + ' '); 376 | 377 | for (var f in orderedFields) { 378 | if (f.isExtension) { 379 | continue; 380 | } 381 | 382 | crc.accumulateString(f.unitType + ' '); 383 | crc.accumulateString(f.name + ' '); 384 | 385 | if (f.parsedType.isArray) { 386 | crc.accumulate(f.parsedType.arrayLength); 387 | } 388 | } 389 | 390 | return (crc.crc & 0xff) ^ (crc.crc >> 8); 391 | } 392 | 393 | /// Length of message bytes that includes extension fields. 394 | int calculateEncodedLength() { 395 | int ret = 0; 396 | for (var f in fields) { 397 | var t = f.parsedType; 398 | ret += (t.bit ~/ 8) * t.arrayLength; 399 | } 400 | 401 | return ret; 402 | } 403 | } 404 | 405 | class DialectField { 406 | final String name; 407 | final String type; 408 | final String description; 409 | final bool isExtension; 410 | final String? units; 411 | final String? enum_; 412 | 413 | final String nameForDart; 414 | 415 | DialectField(this.name, this.type, this.description, this.isExtension, this.units, this.enum_) 416 | : nameForDart = lowerCamelCase(name); 417 | 418 | ParsedMavlinkType get parsedType => 419 | ParsedMavlinkType.parse(type); 420 | 421 | String get unitType { 422 | int indexOfBracket = type.indexOf('['); 423 | if (indexOfBracket == -1) { 424 | return type; 425 | } 426 | return type.substring(0, indexOfBracket); 427 | } 428 | 429 | static DialectField parseElement(XmlElement? elmFiled, isExtension) { 430 | if (elmFiled == null) { 431 | throw FormatException('The filed element must not be null.'); 432 | } 433 | 434 | String name = elmFiled.getAttribute('name') ?? ''; 435 | if (name.isEmpty) { 436 | throw FormatException('The name of message element should not be empty.'); 437 | } 438 | 439 | String type = elmFiled.getAttribute('type') ?? ''; 440 | if (type.isEmpty) { 441 | throw FormatException('The type of message element should not be empty.'); 442 | } 443 | if (type == 'uint8_t_mavlink_version') { 444 | type = 'uint8_t'; 445 | } 446 | 447 | String description = elmFiled.text; 448 | 449 | String? units = elmFiled.getAttribute('units'); 450 | String? enum_ = elmFiled.getAttribute('enum'); 451 | 452 | return DialectField(name, type, description, isExtension, units, enum_); 453 | } 454 | } 455 | 456 | class DialectDocument { 457 | /// This version is included HEATBEAT mavlink_version. 458 | int version = -1; 459 | int dialect = -1; 460 | 461 | /// Enums element. Including enums which is specified by include tags. 462 | DialectEnums enums; 463 | 464 | /// Messages element. Including messages which is specified by include tags. 465 | DialectMessages messages; 466 | 467 | DialectDocument(this.version, this.dialect, this.enums, this.messages); 468 | 469 | static Future parse(String dialectPath) async { 470 | var dialectXml = File(dialectPath); 471 | if (!await dialectXml.exists()) { 472 | throw Exception('$dialectXml does not exist.'); 473 | } 474 | String xmlStr = await dialectXml.readAsString(); 475 | 476 | int version = 0; 477 | int dialect = 0; 478 | DialectEnums dlctEnums = DialectEnums([]); 479 | DialectMessages dlctMessages = DialectMessages([]); 480 | 481 | XmlDocument xmlDoc = XmlDocument.parse(xmlStr); 482 | var elmMavlink = xmlDoc.getElement('mavlink'); 483 | var iterElmInclude = elmMavlink?.findAllElements('include') ?? []; 484 | for (var inc in iterElmInclude) { 485 | var includingPath = path.join(path.dirname(dialectPath), inc.text); 486 | var includingDoc = await DialectDocument.parse(includingPath); 487 | 488 | dlctEnums.addAll(includingDoc.enums); 489 | dlctMessages.addAll(includingDoc.messages); 490 | 491 | // Overwirte values the new include dialect file. 492 | version = (includingDoc.version == -1) ? version : includingDoc.version; 493 | dialect = (includingDoc.dialect == -1) ? dialect : includingDoc.dialect; 494 | 495 | // Add/overwrite values. 496 | } 497 | 498 | // version tag 499 | var t = elmMavlink?.getElement('version')?.text; 500 | if (t != null) { 501 | version = int.parse(t); 502 | } 503 | 504 | // dialect tag 505 | t = elmMavlink?.getElement('dialect')?.text; 506 | if (t != null) { 507 | dialect = int.parse(t); 508 | } 509 | 510 | // Enum tag 511 | dlctEnums.addAll(DialectEnums.parseElement(elmMavlink?.getElement('enums'))); 512 | 513 | // Message Definition 514 | dlctMessages.addAll(DialectMessages.parseElement(elmMavlink?.getElement('messages'))); 515 | 516 | return DialectDocument(version, dialect, dlctEnums, dlctMessages); 517 | } 518 | } 519 | 520 | String capitalize(String s) { 521 | return s[0].toUpperCase() + s.substring(1).toLowerCase(); 522 | } 523 | 524 | String camelCase(String s) { 525 | s = s.toLowerCase(); 526 | var sep = s.split('_'); 527 | return sep.map((e) => capitalize(e)).join(''); 528 | } 529 | 530 | String lowerCamelCase(String s) { 531 | s = s.toLowerCase(); 532 | var sep = s.split('_'); 533 | if (sep.length == 1) { 534 | return sep[0]; 535 | } 536 | 537 | return sep[0] + sep.sublist(1).map((e) => capitalize(e)).join(''); 538 | } 539 | 540 | String dialectNameFromPath(String p) { 541 | String b = path.basenameWithoutExtension(p); 542 | return capitalize(b); 543 | } 544 | 545 | enum BasicType { 546 | int, 547 | uint, 548 | float, 549 | } 550 | 551 | class ParsedMavlinkType { 552 | final BasicType type; 553 | final int bit; 554 | 555 | /// Length of array. 1 or above. 1 means not an array. 556 | final int arrayLength; 557 | 558 | final String mavlinkType; 559 | 560 | ParsedMavlinkType(this.type, this.bit, this.arrayLength, this.mavlinkType); 561 | 562 | bool get isArray => arrayLength > 1; 563 | 564 | int get byte => bit ~/ 8; 565 | 566 | factory ParsedMavlinkType.parse(String mavlinkType) { 567 | var m = RegExp(r'(uint|int|char|float|double)(8|16|32|64|)(_t|_t_mavlink_version|)(\[(\d{1,3})\]|)').firstMatch(mavlinkType); 568 | if ((m == null) || m.groupCount != 5) { 569 | throw FormatException('Unexpected type, $mavlinkType'); 570 | } 571 | 572 | // print('m: ${[for (var i = 0; i < m.groupCount+1; i++) m.group(i)]}'); // For debugging 573 | 574 | var arrayLength = 1; 575 | if (m.group(5) != null) { 576 | // Get array size, 2 or above. 577 | arrayLength = int.parse(m.group(5)!); 578 | } 579 | 580 | var t = BasicType.int; // type 581 | var b = 8; // bit 582 | switch (m.group(1)) { 583 | case 'int': 584 | t = BasicType.int; 585 | b = int.parse(m.group(2)!); 586 | break; 587 | case 'uint': 588 | t = BasicType.uint; 589 | b = int.parse(m.group(2)!); 590 | break; 591 | case 'char': 592 | t = BasicType.int; 593 | b = 8; 594 | break; 595 | case 'float': 596 | t = BasicType.float; 597 | b = 32; 598 | break; 599 | case 'double': 600 | t = BasicType.float; 601 | b = 64; 602 | break; 603 | default: 604 | throw FormatException('Unexpected type, ${m.group(1)}'); 605 | } 606 | 607 | return ParsedMavlinkType(t, b, arrayLength, mavlinkType); 608 | } 609 | } 610 | 611 | Future generateCode(String dstPath, String srcDialectPath) async { 612 | var doc = await DialectDocument.parse(srcDialectPath); 613 | 614 | String content = ''; 615 | 616 | content += "import 'dart:typed_data';\n"; 617 | content += "import 'package:dart_mavlink/mavlink_dialect.dart';\n"; 618 | content += "import 'package:dart_mavlink/mavlink_message.dart';\n"; 619 | content += "import 'package:dart_mavlink/types.dart';\n"; 620 | 621 | // Write enum fields 622 | for (var enm in doc.enums) { 623 | content += '\n'; 624 | if (enm.description != null) { 625 | content += generateAsDartDocumentation(enm.description!); 626 | } 627 | content += '///\n'; 628 | content += '/// ${enm.name}\n'; 629 | content += 'typedef ${enm.nameForDart} = int;\n'; 630 | 631 | if (enm.entries != null) { 632 | for (var entry in enm.entries!) { 633 | if (entry.wip) { 634 | content += '/// WIP.\n'; 635 | } 636 | if (entry.description != null) { 637 | content += generateAsDartDocumentation(entry.description!); 638 | } 639 | content += '///\n'; 640 | content += '/// ${entry.name}\n'; 641 | if (entry.deprecated != null) { 642 | content += '@Deprecated("Replaced by [${entry.deprecated!.replacedBy}] since ${entry.deprecated!.since}. ${entry.deprecated!.text}")\n'; 643 | } 644 | content += 'const ${enm.nameForDart} ${entry.nameForDart} = ${entry.value};\n'; 645 | } 646 | } 647 | } 648 | 649 | // Wrirte message classes. 650 | for (var msg in doc.messages) { 651 | content += generateAsDartDocumentation(msg.description); 652 | content += '///\n'; 653 | content += '/// ${msg.name}\n'; 654 | content += 'class ${msg.nameForDart} implements MavlinkMessage {\n'; 655 | content += '\n'; 656 | content += 'static const int _mavlinkMessageId = ${msg.id};\n'; 657 | content += '\n'; 658 | content += 'static const int _mavlinkCrcExtra = ${msg.calculateCrcExtra()};\n'; 659 | content += '\n'; 660 | content += 'static const int mavlinkEncodedLength = ${msg.calculateEncodedLength()};\n'; 661 | 662 | content +='\n'; 663 | content +='@override int get mavlinkMessageId => _mavlinkMessageId;\n'; 664 | content +='\n'; 665 | content +='@override int get mavlinkCrcExtra => _mavlinkCrcExtra;\n'; 666 | 667 | for (var field in msg.orderedFields) { 668 | content += generateAsDartDocumentation(field.description); 669 | content += '///\n'; 670 | content += '/// MAVLink type: ${field.type}\n'; 671 | if (field.units != null) { 672 | content += '///\n'; 673 | content += '/// units: ${field.units!}\n'; 674 | } 675 | if (field.enum_ != null) { 676 | content += '///\n'; 677 | content += '/// enum: [${camelCase(field.enum_!)}]\n'; 678 | } 679 | if (field.isExtension) { 680 | content += '///\n'; 681 | content += '/// Extensions field for MAVLink 2.\n'; 682 | } 683 | content += '///\n'; 684 | content += '/// ${field.name}\n'; 685 | content += 'final ${asDartType(field.type, field.enum_)} ${field.nameForDart};\n'; 686 | } 687 | content += '\n'; 688 | 689 | // Constructor 690 | content += '${msg.nameForDart}({'; 691 | String arrayInitializationCode = ''; 692 | for(var f in msg.orderedFields) { 693 | content += 'required this.${f.nameForDart}, '; 694 | } 695 | if (arrayInitializationCode.isEmpty) { 696 | content += '});\n'; 697 | } else { 698 | content += '})\n'; 699 | content += ':' + arrayInitializationCode.substring(0, arrayInitializationCode.length - 1) + ';'; 700 | } 701 | content += '\n'; 702 | 703 | // copyWith builder 704 | content += '${msg.nameForDart} copyWith({\n'; 705 | for (var f in msg.orderedFields) { 706 | content += '${asDartType(f.type, f.enum_)}? ${f.nameForDart},\n'; 707 | } 708 | content += '}){\n'; 709 | content += 'return ${msg.nameForDart}(\n'; 710 | for (var f in msg.orderedFields) { 711 | content += 712 | '${f.nameForDart}: ${f.nameForDart} ?? this.${f.nameForDart},\n'; 713 | } 714 | content += ');'; 715 | content += '}'; 716 | 717 | // parse constructor. 718 | content += '''factory ${msg.nameForDart}.parse(ByteData data_) { 719 | if (data_.lengthInBytes < ${msg.nameForDart}.mavlinkEncodedLength) { 720 | var len = ${msg.nameForDart}.mavlinkEncodedLength - data_.lengthInBytes; 721 | var d = data_.buffer.asUint8List().sublist(0, data_.lengthInBytes) + List.filled(len, 0); 722 | data_ = Uint8List.fromList(d).buffer.asByteData(); 723 | } 724 | '''; 725 | 726 | int byteOffset = 0; 727 | for(var f in msg.orderedFields) { 728 | var t = f.parsedType; 729 | 730 | var endianArgument = t.bit == 8 ? '' : ', Endian.little'; 731 | if (t.isArray) { 732 | // Array type 733 | switch (t.type) { 734 | case BasicType.int: 735 | content += 'var ${f.nameForDart} = MavlinkMessage.asInt${t.bit}List(data_, $byteOffset, ${t.arrayLength});\n'; 736 | break; 737 | case BasicType.uint: 738 | content += 'var ${f.nameForDart} = MavlinkMessage.asUint${t.bit}List(data_, $byteOffset, ${t.arrayLength});\n'; 739 | break; 740 | case BasicType.float: 741 | content += 'var ${f.nameForDart} = MavlinkMessage.asFloat${t.bit}List(data_, $byteOffset, ${t.arrayLength});\n'; 742 | break; 743 | } 744 | } else { 745 | switch (t.type) { 746 | case BasicType.int: 747 | content += 'var ${f.nameForDart} = data_.getInt${t.bit}($byteOffset$endianArgument);\n'; 748 | break; 749 | case BasicType.uint: 750 | content += 'var ${f.nameForDart} = data_.getUint${t.bit}($byteOffset$endianArgument);\n'; 751 | break; 752 | case BasicType.float: 753 | content += 'var ${f.nameForDart} = data_.getFloat${t.bit}($byteOffset, Endian.little);\n'; 754 | break; 755 | } 756 | } 757 | 758 | byteOffset += t.byte * t.arrayLength; 759 | } 760 | content += '\n'; 761 | content += 'return ${msg.nameForDart}('; 762 | content += [ 763 | for(var f in msg.orderedFields) 764 | '${f.nameForDart}: ${f.nameForDart}' 765 | ] 766 | .join(', '); 767 | content += ');\n'; 768 | content += '}\n'; 769 | content += '\n'; 770 | 771 | // serialize 772 | content += '''@override 773 | ByteData serialize() { 774 | var data_ = ByteData(mavlinkEncodedLength);'''; 775 | byteOffset = 0; 776 | for(var f in msg.orderedFields) { 777 | var t = f.parsedType; 778 | 779 | var endianArgument = t.bit == 8 ? '' : ', Endian.little'; 780 | if (t.isArray) { 781 | switch (t.type) { 782 | case BasicType.int: 783 | content += 'MavlinkMessage.setInt${t.bit}List(data_, $byteOffset, ${f.nameForDart});\n'; 784 | break; 785 | case BasicType.uint: 786 | content += 'MavlinkMessage.setUint${t.bit}List(data_, $byteOffset, ${f.nameForDart});\n'; 787 | break; 788 | case BasicType.float: 789 | content += 'MavlinkMessage.setFloat${t.bit}List(data_, $byteOffset, ${f.nameForDart});\n'; 790 | break; 791 | } 792 | } else { 793 | switch (t.type) { 794 | case BasicType.int: 795 | content += 'data_.setInt${t.bit}($byteOffset, ${f.nameForDart}$endianArgument);\n'; 796 | break; 797 | case BasicType.uint: 798 | content += 'data_.setUint${t.bit}($byteOffset, ${f.nameForDart}$endianArgument);\n'; 799 | break; 800 | case BasicType.float: 801 | content += 'data_.setFloat${t.bit}($byteOffset, ${f.nameForDart}, Endian.little);\n'; 802 | break; 803 | } 804 | } 805 | 806 | byteOffset += (t.bit ~/ 8) * t.arrayLength; 807 | } 808 | 809 | content += 'return data_;\n'; 810 | content += '}\n'; 811 | 812 | content += '}\n'; 813 | } 814 | 815 | // Interface for MavlinkDialect. 816 | String dialectName = dialectNameFromPath(srcDialectPath); 817 | content += ''' 818 | class MavlinkDialect$dialectName implements MavlinkDialect { 819 | static const int mavlinkVersion = ${doc.version}; 820 | 821 | @override 822 | int get version => mavlinkVersion; 823 | 824 | @override 825 | MavlinkMessage? parse(int messageID, ByteData data) { 826 | switch (messageID) { 827 | '''; 828 | 829 | for (var msg in doc.messages) { 830 | content += '''case ${msg.id}: 831 | return ${msg.nameForDart}.parse(data); 832 | '''; 833 | } 834 | content += 'default:\n'; 835 | content += 'return null;\n'; 836 | content += '}\n'; 837 | content += '}\n'; 838 | 839 | content += ''' 840 | @override 841 | int crcExtra(int messageID) { 842 | switch (messageID) { 843 | '''; 844 | for (var msg in doc.messages) { 845 | content += '''case ${msg.id}: 846 | return ${msg.nameForDart}._mavlinkCrcExtra; 847 | '''; 848 | } 849 | 850 | content += ''' 851 | default: 852 | return -1; 853 | } 854 | } 855 | } 856 | '''; 857 | 858 | var outDart = File(dstPath); 859 | await outDart.writeAsString(content); 860 | return true; 861 | } 862 | 863 | String generateAsDartDocumentation(String str) 864 | => str.split('\n').map((s) => '/// ' + s.trimLeft()).join('\n') + '\n'; 865 | 866 | String asDartType(String mavlinkType, String? enum_) { 867 | var basicTypes = [ 868 | 'int8_t', 869 | 'uint8_t', 870 | 'int16_t', 871 | 'uint16_t', 872 | 'int32_t', 873 | 'uint32_t', 874 | 'int64_t', 875 | 'uint64_t', 876 | 'char', 877 | 'float', 878 | 'double', 879 | ]; 880 | for (var type in basicTypes) { 881 | if (type == mavlinkType) { 882 | if (enum_ != null) { 883 | return camelCase(enum_); 884 | } 885 | return mavlinkType; 886 | } 887 | if (RegExp(type + r'\[\d{1,3}\]').hasMatch(mavlinkType)) { 888 | if (enum_ != null) { 889 | return 'List<${camelCase(enum_)}>'; 890 | } 891 | return 'List<$type>'; 892 | } 893 | } 894 | return 'Unknown($mavlinkType)'; 895 | } 896 | 897 | Future runFormatter(String path) async { 898 | await Process.run('dart', ['format', path]); 899 | } 900 | 901 | void main() async { 902 | final dir = await Directory('mavlink/message_definitions/v1.0/').list() 903 | .map((f) => f.path.toString()) 904 | .where((f) => 905 | (!f.endsWith('all.xml')) && (!f.contains('test')) 906 | ) 907 | .toList(); 908 | 909 | var dstDir = 'lib/dialects'; 910 | await Directory(dstDir).create(recursive: true); 911 | 912 | for (var xmlPath in dir) { 913 | print(xmlPath); 914 | var dartPath = path.join(dstDir, path.basenameWithoutExtension(xmlPath).toLowerCase() + '.dart'); 915 | await generateCode(dartPath, xmlPath); 916 | await runFormatter(dartPath); 917 | } 918 | } 919 | -------------------------------------------------------------------------------- /lib/dialects/minimal.dart: -------------------------------------------------------------------------------- 1 | import 'dart:typed_data'; 2 | import 'package:dart_mavlink/mavlink_dialect.dart'; 3 | import 'package:dart_mavlink/mavlink_message.dart'; 4 | import 'package:dart_mavlink/types.dart'; 5 | 6 | /// Micro air vehicle / autopilot classes. This identifies the individual model. 7 | /// 8 | /// MAV_AUTOPILOT 9 | typedef MavAutopilot = int; 10 | 11 | /// Generic autopilot, full support for everything 12 | /// 13 | /// MAV_AUTOPILOT_GENERIC 14 | const MavAutopilot mavAutopilotGeneric = 0; 15 | 16 | /// Reserved for future use. 17 | /// 18 | /// MAV_AUTOPILOT_RESERVED 19 | const MavAutopilot mavAutopilotReserved = 1; 20 | 21 | /// SLUGS autopilot, http://slugsuav.soe.ucsc.edu 22 | /// 23 | /// MAV_AUTOPILOT_SLUGS 24 | const MavAutopilot mavAutopilotSlugs = 2; 25 | 26 | /// ArduPilot - Plane/Copter/Rover/Sub/Tracker, https://ardupilot.org 27 | /// 28 | /// MAV_AUTOPILOT_ARDUPILOTMEGA 29 | const MavAutopilot mavAutopilotArdupilotmega = 3; 30 | 31 | /// OpenPilot, http://openpilot.org 32 | /// 33 | /// MAV_AUTOPILOT_OPENPILOT 34 | const MavAutopilot mavAutopilotOpenpilot = 4; 35 | 36 | /// Generic autopilot only supporting simple waypoints 37 | /// 38 | /// MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY 39 | const MavAutopilot mavAutopilotGenericWaypointsOnly = 5; 40 | 41 | /// Generic autopilot supporting waypoints and other simple navigation commands 42 | /// 43 | /// MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY 44 | const MavAutopilot mavAutopilotGenericWaypointsAndSimpleNavigationOnly = 6; 45 | 46 | /// Generic autopilot supporting the full mission command set 47 | /// 48 | /// MAV_AUTOPILOT_GENERIC_MISSION_FULL 49 | const MavAutopilot mavAutopilotGenericMissionFull = 7; 50 | 51 | /// No valid autopilot, e.g. a GCS or other MAVLink component 52 | /// 53 | /// MAV_AUTOPILOT_INVALID 54 | const MavAutopilot mavAutopilotInvalid = 8; 55 | 56 | /// PPZ UAV - http://nongnu.org/paparazzi 57 | /// 58 | /// MAV_AUTOPILOT_PPZ 59 | const MavAutopilot mavAutopilotPpz = 9; 60 | 61 | /// UAV Dev Board 62 | /// 63 | /// MAV_AUTOPILOT_UDB 64 | const MavAutopilot mavAutopilotUdb = 10; 65 | 66 | /// FlexiPilot 67 | /// 68 | /// MAV_AUTOPILOT_FP 69 | const MavAutopilot mavAutopilotFp = 11; 70 | 71 | /// PX4 Autopilot - http://px4.io/ 72 | /// 73 | /// MAV_AUTOPILOT_PX4 74 | const MavAutopilot mavAutopilotPx4 = 12; 75 | 76 | /// SMACCMPilot - http://smaccmpilot.org 77 | /// 78 | /// MAV_AUTOPILOT_SMACCMPILOT 79 | const MavAutopilot mavAutopilotSmaccmpilot = 13; 80 | 81 | /// AutoQuad -- http://autoquad.org 82 | /// 83 | /// MAV_AUTOPILOT_AUTOQUAD 84 | const MavAutopilot mavAutopilotAutoquad = 14; 85 | 86 | /// Armazila -- http://armazila.com 87 | /// 88 | /// MAV_AUTOPILOT_ARMAZILA 89 | const MavAutopilot mavAutopilotArmazila = 15; 90 | 91 | /// Aerob -- http://aerob.ru 92 | /// 93 | /// MAV_AUTOPILOT_AEROB 94 | const MavAutopilot mavAutopilotAerob = 16; 95 | 96 | /// ASLUAV autopilot -- http://www.asl.ethz.ch 97 | /// 98 | /// MAV_AUTOPILOT_ASLUAV 99 | const MavAutopilot mavAutopilotAsluav = 17; 100 | 101 | /// SmartAP Autopilot - http://sky-drones.com 102 | /// 103 | /// MAV_AUTOPILOT_SMARTAP 104 | const MavAutopilot mavAutopilotSmartap = 18; 105 | 106 | /// AirRails - http://uaventure.com 107 | /// 108 | /// MAV_AUTOPILOT_AIRRAILS 109 | const MavAutopilot mavAutopilotAirrails = 19; 110 | 111 | /// Fusion Reflex - https://fusion.engineering 112 | /// 113 | /// MAV_AUTOPILOT_REFLEX 114 | const MavAutopilot mavAutopilotReflex = 20; 115 | 116 | /// MAVLINK component type reported in HEARTBEAT message. Flight controllers must report the type of the vehicle on which they are mounted (e.g. MAV_TYPE_OCTOROTOR). All other components must report a value appropriate for their type (e.g. a camera must use MAV_TYPE_CAMERA). 117 | /// 118 | /// MAV_TYPE 119 | typedef MavType = int; 120 | 121 | /// Generic micro air vehicle 122 | /// 123 | /// MAV_TYPE_GENERIC 124 | const MavType mavTypeGeneric = 0; 125 | 126 | /// Fixed wing aircraft. 127 | /// 128 | /// MAV_TYPE_FIXED_WING 129 | const MavType mavTypeFixedWing = 1; 130 | 131 | /// Quadrotor 132 | /// 133 | /// MAV_TYPE_QUADROTOR 134 | const MavType mavTypeQuadrotor = 2; 135 | 136 | /// Coaxial helicopter 137 | /// 138 | /// MAV_TYPE_COAXIAL 139 | const MavType mavTypeCoaxial = 3; 140 | 141 | /// Normal helicopter with tail rotor. 142 | /// 143 | /// MAV_TYPE_HELICOPTER 144 | const MavType mavTypeHelicopter = 4; 145 | 146 | /// Ground installation 147 | /// 148 | /// MAV_TYPE_ANTENNA_TRACKER 149 | const MavType mavTypeAntennaTracker = 5; 150 | 151 | /// Operator control unit / ground control station 152 | /// 153 | /// MAV_TYPE_GCS 154 | const MavType mavTypeGcs = 6; 155 | 156 | /// Airship, controlled 157 | /// 158 | /// MAV_TYPE_AIRSHIP 159 | const MavType mavTypeAirship = 7; 160 | 161 | /// Free balloon, uncontrolled 162 | /// 163 | /// MAV_TYPE_FREE_BALLOON 164 | const MavType mavTypeFreeBalloon = 8; 165 | 166 | /// Rocket 167 | /// 168 | /// MAV_TYPE_ROCKET 169 | const MavType mavTypeRocket = 9; 170 | 171 | /// Ground rover 172 | /// 173 | /// MAV_TYPE_GROUND_ROVER 174 | const MavType mavTypeGroundRover = 10; 175 | 176 | /// Surface vessel, boat, ship 177 | /// 178 | /// MAV_TYPE_SURFACE_BOAT 179 | const MavType mavTypeSurfaceBoat = 11; 180 | 181 | /// Submarine 182 | /// 183 | /// MAV_TYPE_SUBMARINE 184 | const MavType mavTypeSubmarine = 12; 185 | 186 | /// Hexarotor 187 | /// 188 | /// MAV_TYPE_HEXAROTOR 189 | const MavType mavTypeHexarotor = 13; 190 | 191 | /// Octorotor 192 | /// 193 | /// MAV_TYPE_OCTOROTOR 194 | const MavType mavTypeOctorotor = 14; 195 | 196 | /// Tricopter 197 | /// 198 | /// MAV_TYPE_TRICOPTER 199 | const MavType mavTypeTricopter = 15; 200 | 201 | /// Flapping wing 202 | /// 203 | /// MAV_TYPE_FLAPPING_WING 204 | const MavType mavTypeFlappingWing = 16; 205 | 206 | /// Kite 207 | /// 208 | /// MAV_TYPE_KITE 209 | const MavType mavTypeKite = 17; 210 | 211 | /// Onboard companion controller 212 | /// 213 | /// MAV_TYPE_ONBOARD_CONTROLLER 214 | const MavType mavTypeOnboardController = 18; 215 | 216 | /// Two-rotor Tailsitter VTOL that additionally uses control surfaces in vertical operation. Note, value previously named MAV_TYPE_VTOL_DUOROTOR. 217 | /// 218 | /// MAV_TYPE_VTOL_TAILSITTER_DUOROTOR 219 | const MavType mavTypeVtolTailsitterDuorotor = 19; 220 | 221 | /// Quad-rotor Tailsitter VTOL using a V-shaped quad config in vertical operation. Note: value previously named MAV_TYPE_VTOL_QUADROTOR. 222 | /// 223 | /// MAV_TYPE_VTOL_TAILSITTER_QUADROTOR 224 | const MavType mavTypeVtolTailsitterQuadrotor = 20; 225 | 226 | /// Tiltrotor VTOL. Fuselage and wings stay (nominally) horizontal in all flight phases. It able to tilt (some) rotors to provide thrust in cruise flight. 227 | /// 228 | /// MAV_TYPE_VTOL_TILTROTOR 229 | const MavType mavTypeVtolTiltrotor = 21; 230 | 231 | /// VTOL with separate fixed rotors for hover and cruise flight. Fuselage and wings stay (nominally) horizontal in all flight phases. 232 | /// 233 | /// MAV_TYPE_VTOL_FIXEDROTOR 234 | const MavType mavTypeVtolFixedrotor = 22; 235 | 236 | /// Tailsitter VTOL. Fuselage and wings orientation changes depending on flight phase: vertical for hover, horizontal for cruise. Use more specific VTOL MAV_TYPE_VTOL_TAILSITTER_DUOROTOR or MAV_TYPE_VTOL_TAILSITTER_QUADROTOR if appropriate. 237 | /// 238 | /// MAV_TYPE_VTOL_TAILSITTER 239 | const MavType mavTypeVtolTailsitter = 23; 240 | 241 | /// Tiltwing VTOL. Fuselage stays horizontal in all flight phases. The whole wing, along with any attached engine, can tilt between vertical and horizontal mode. 242 | /// 243 | /// MAV_TYPE_VTOL_TILTWING 244 | const MavType mavTypeVtolTiltwing = 24; 245 | 246 | /// VTOL reserved 5 247 | /// 248 | /// MAV_TYPE_VTOL_RESERVED5 249 | const MavType mavTypeVtolReserved5 = 25; 250 | 251 | /// Gimbal 252 | /// 253 | /// MAV_TYPE_GIMBAL 254 | const MavType mavTypeGimbal = 26; 255 | 256 | /// ADSB system 257 | /// 258 | /// MAV_TYPE_ADSB 259 | const MavType mavTypeAdsb = 27; 260 | 261 | /// Steerable, nonrigid airfoil 262 | /// 263 | /// MAV_TYPE_PARAFOIL 264 | const MavType mavTypeParafoil = 28; 265 | 266 | /// Dodecarotor 267 | /// 268 | /// MAV_TYPE_DODECAROTOR 269 | const MavType mavTypeDodecarotor = 29; 270 | 271 | /// Camera 272 | /// 273 | /// MAV_TYPE_CAMERA 274 | const MavType mavTypeCamera = 30; 275 | 276 | /// Charging station 277 | /// 278 | /// MAV_TYPE_CHARGING_STATION 279 | const MavType mavTypeChargingStation = 31; 280 | 281 | /// FLARM collision avoidance system 282 | /// 283 | /// MAV_TYPE_FLARM 284 | const MavType mavTypeFlarm = 32; 285 | 286 | /// Servo 287 | /// 288 | /// MAV_TYPE_SERVO 289 | const MavType mavTypeServo = 33; 290 | 291 | /// Open Drone ID. See https://mavlink.io/en/services/opendroneid.html. 292 | /// 293 | /// MAV_TYPE_ODID 294 | const MavType mavTypeOdid = 34; 295 | 296 | /// Decarotor 297 | /// 298 | /// MAV_TYPE_DECAROTOR 299 | const MavType mavTypeDecarotor = 35; 300 | 301 | /// Battery 302 | /// 303 | /// MAV_TYPE_BATTERY 304 | const MavType mavTypeBattery = 36; 305 | 306 | /// Parachute 307 | /// 308 | /// MAV_TYPE_PARACHUTE 309 | const MavType mavTypeParachute = 37; 310 | 311 | /// Log 312 | /// 313 | /// MAV_TYPE_LOG 314 | const MavType mavTypeLog = 38; 315 | 316 | /// OSD 317 | /// 318 | /// MAV_TYPE_OSD 319 | const MavType mavTypeOsd = 39; 320 | 321 | /// IMU 322 | /// 323 | /// MAV_TYPE_IMU 324 | const MavType mavTypeImu = 40; 325 | 326 | /// GPS 327 | /// 328 | /// MAV_TYPE_GPS 329 | const MavType mavTypeGps = 41; 330 | 331 | /// Winch 332 | /// 333 | /// MAV_TYPE_WINCH 334 | const MavType mavTypeWinch = 42; 335 | 336 | /// Generic multirotor that does not fit into a specific type or whose type is unknown 337 | /// 338 | /// MAV_TYPE_GENERIC_MULTIROTOR 339 | const MavType mavTypeGenericMultirotor = 43; 340 | 341 | /// Illuminator. An illuminator is a light source that is used for lighting up dark areas external to the sytstem: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light). 342 | /// 343 | /// MAV_TYPE_ILLUMINATOR 344 | const MavType mavTypeIlluminator = 44; 345 | 346 | /// These flags encode the MAV mode. 347 | /// 348 | /// MAV_MODE_FLAG 349 | typedef MavModeFlag = int; 350 | 351 | /// 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. Additional note: this flag is to be ignore when sent in the command MAV_CMD_DO_SET_MODE and MAV_CMD_COMPONENT_ARM_DISARM shall be used instead. The flag can still be used to report the armed state. 352 | /// 353 | /// MAV_MODE_FLAG_SAFETY_ARMED 354 | const MavModeFlag mavModeFlagSafetyArmed = 128; 355 | 356 | /// 0b01000000 remote control input is enabled. 357 | /// 358 | /// MAV_MODE_FLAG_MANUAL_INPUT_ENABLED 359 | const MavModeFlag mavModeFlagManualInputEnabled = 64; 360 | 361 | /// 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. 362 | /// 363 | /// MAV_MODE_FLAG_HIL_ENABLED 364 | const MavModeFlag mavModeFlagHilEnabled = 32; 365 | 366 | /// 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. 367 | /// 368 | /// MAV_MODE_FLAG_STABILIZE_ENABLED 369 | const MavModeFlag mavModeFlagStabilizeEnabled = 16; 370 | 371 | /// 0b00001000 guided mode enabled, system flies waypoints / mission items. 372 | /// 373 | /// MAV_MODE_FLAG_GUIDED_ENABLED 374 | const MavModeFlag mavModeFlagGuidedEnabled = 8; 375 | 376 | /// 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. 377 | /// 378 | /// MAV_MODE_FLAG_AUTO_ENABLED 379 | const MavModeFlag mavModeFlagAutoEnabled = 4; 380 | 381 | /// 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. 382 | /// 383 | /// MAV_MODE_FLAG_TEST_ENABLED 384 | const MavModeFlag mavModeFlagTestEnabled = 2; 385 | 386 | /// 0b00000001 Reserved for future use. 387 | /// 388 | /// MAV_MODE_FLAG_CUSTOM_MODE_ENABLED 389 | const MavModeFlag mavModeFlagCustomModeEnabled = 1; 390 | 391 | /// These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. 392 | /// 393 | /// MAV_MODE_FLAG_DECODE_POSITION 394 | typedef MavModeFlagDecodePosition = int; 395 | 396 | /// First bit: 10000000 397 | /// 398 | /// MAV_MODE_FLAG_DECODE_POSITION_SAFETY 399 | const MavModeFlagDecodePosition mavModeFlagDecodePositionSafety = 128; 400 | 401 | /// Second bit: 01000000 402 | /// 403 | /// MAV_MODE_FLAG_DECODE_POSITION_MANUAL 404 | const MavModeFlagDecodePosition mavModeFlagDecodePositionManual = 64; 405 | 406 | /// Third bit: 00100000 407 | /// 408 | /// MAV_MODE_FLAG_DECODE_POSITION_HIL 409 | const MavModeFlagDecodePosition mavModeFlagDecodePositionHil = 32; 410 | 411 | /// Fourth bit: 00010000 412 | /// 413 | /// MAV_MODE_FLAG_DECODE_POSITION_STABILIZE 414 | const MavModeFlagDecodePosition mavModeFlagDecodePositionStabilize = 16; 415 | 416 | /// Fifth bit: 00001000 417 | /// 418 | /// MAV_MODE_FLAG_DECODE_POSITION_GUIDED 419 | const MavModeFlagDecodePosition mavModeFlagDecodePositionGuided = 8; 420 | 421 | /// Sixth bit: 00000100 422 | /// 423 | /// MAV_MODE_FLAG_DECODE_POSITION_AUTO 424 | const MavModeFlagDecodePosition mavModeFlagDecodePositionAuto = 4; 425 | 426 | /// Seventh bit: 00000010 427 | /// 428 | /// MAV_MODE_FLAG_DECODE_POSITION_TEST 429 | const MavModeFlagDecodePosition mavModeFlagDecodePositionTest = 2; 430 | 431 | /// Eighth bit: 00000001 432 | /// 433 | /// MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE 434 | const MavModeFlagDecodePosition mavModeFlagDecodePositionCustomMode = 1; 435 | 436 | /// 437 | /// MAV_STATE 438 | typedef MavState = int; 439 | 440 | /// Uninitialized system, state is unknown. 441 | /// 442 | /// MAV_STATE_UNINIT 443 | const MavState mavStateUninit = 0; 444 | 445 | /// System is booting up. 446 | /// 447 | /// MAV_STATE_BOOT 448 | const MavState mavStateBoot = 1; 449 | 450 | /// System is calibrating and not flight-ready. 451 | /// 452 | /// MAV_STATE_CALIBRATING 453 | const MavState mavStateCalibrating = 2; 454 | 455 | /// System is grounded and on standby. It can be launched any time. 456 | /// 457 | /// MAV_STATE_STANDBY 458 | const MavState mavStateStandby = 3; 459 | 460 | /// System is active and might be already airborne. Motors are engaged. 461 | /// 462 | /// MAV_STATE_ACTIVE 463 | const MavState mavStateActive = 4; 464 | 465 | /// System is in a non-normal flight mode (failsafe). It can however still navigate. 466 | /// 467 | /// MAV_STATE_CRITICAL 468 | const MavState mavStateCritical = 5; 469 | 470 | /// System is in a non-normal flight mode (failsafe). It lost control over parts or over the whole airframe. It is in mayday and going down. 471 | /// 472 | /// MAV_STATE_EMERGENCY 473 | const MavState mavStateEmergency = 6; 474 | 475 | /// System just initialized its power-down sequence, will shut down now. 476 | /// 477 | /// MAV_STATE_POWEROFF 478 | const MavState mavStatePoweroff = 7; 479 | 480 | /// System is terminating itself (failsafe or commanded). 481 | /// 482 | /// MAV_STATE_FLIGHT_TERMINATION 483 | const MavState mavStateFlightTermination = 8; 484 | 485 | /// Component ids (values) for the different types and instances of onboard hardware/software that might make up a MAVLink system (autopilot, cameras, servos, GPS systems, avoidance systems etc.). 486 | /// Components must use the appropriate ID in their source address when sending messages. Components can also use IDs to determine if they are the intended recipient of an incoming message. The MAV_COMP_ID_ALL value is used to indicate messages that must be processed by all components. 487 | /// When creating new entries, components that can have multiple instances (e.g. cameras, servos etc.) should be allocated sequential values. An appropriate number of values should be left free after these components to allow the number of instances to be expanded. 488 | /// 489 | /// MAV_COMPONENT 490 | typedef MavComponent = int; 491 | 492 | /// Target id (target_component) used to broadcast messages to all components of the receiving system. Components should attempt to process messages with this component ID and forward to components on any other interfaces. Note: This is not a valid *source* component id for a message. 493 | /// 494 | /// MAV_COMP_ID_ALL 495 | const MavComponent mavCompIdAll = 0; 496 | 497 | /// System flight controller component ("autopilot"). Only one autopilot is expected in a particular system. 498 | /// 499 | /// MAV_COMP_ID_AUTOPILOT1 500 | const MavComponent mavCompIdAutopilot1 = 1; 501 | 502 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 503 | /// 504 | /// MAV_COMP_ID_USER1 505 | const MavComponent mavCompIdUser1 = 25; 506 | 507 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 508 | /// 509 | /// MAV_COMP_ID_USER2 510 | const MavComponent mavCompIdUser2 = 26; 511 | 512 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 513 | /// 514 | /// MAV_COMP_ID_USER3 515 | const MavComponent mavCompIdUser3 = 27; 516 | 517 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 518 | /// 519 | /// MAV_COMP_ID_USER4 520 | const MavComponent mavCompIdUser4 = 28; 521 | 522 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 523 | /// 524 | /// MAV_COMP_ID_USER5 525 | const MavComponent mavCompIdUser5 = 29; 526 | 527 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 528 | /// 529 | /// MAV_COMP_ID_USER6 530 | const MavComponent mavCompIdUser6 = 30; 531 | 532 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 533 | /// 534 | /// MAV_COMP_ID_USER7 535 | const MavComponent mavCompIdUser7 = 31; 536 | 537 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 538 | /// 539 | /// MAV_COMP_ID_USER8 540 | const MavComponent mavCompIdUser8 = 32; 541 | 542 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 543 | /// 544 | /// MAV_COMP_ID_USER9 545 | const MavComponent mavCompIdUser9 = 33; 546 | 547 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 548 | /// 549 | /// MAV_COMP_ID_USER10 550 | const MavComponent mavCompIdUser10 = 34; 551 | 552 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 553 | /// 554 | /// MAV_COMP_ID_USER11 555 | const MavComponent mavCompIdUser11 = 35; 556 | 557 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 558 | /// 559 | /// MAV_COMP_ID_USER12 560 | const MavComponent mavCompIdUser12 = 36; 561 | 562 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 563 | /// 564 | /// MAV_COMP_ID_USER13 565 | const MavComponent mavCompIdUser13 = 37; 566 | 567 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 568 | /// 569 | /// MAV_COMP_ID_USER14 570 | const MavComponent mavCompIdUser14 = 38; 571 | 572 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 573 | /// 574 | /// MAV_COMP_ID_USER15 575 | const MavComponent mavCompIdUser15 = 39; 576 | 577 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 578 | /// 579 | /// MAV_COMP_ID_USER16 580 | const MavComponent mavCompIdUser16 = 40; 581 | 582 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 583 | /// 584 | /// MAV_COMP_ID_USER17 585 | const MavComponent mavCompIdUser17 = 41; 586 | 587 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 588 | /// 589 | /// MAV_COMP_ID_USER18 590 | const MavComponent mavCompIdUser18 = 42; 591 | 592 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 593 | /// 594 | /// MAV_COMP_ID_USER19 595 | const MavComponent mavCompIdUser19 = 43; 596 | 597 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 598 | /// 599 | /// MAV_COMP_ID_USER20 600 | const MavComponent mavCompIdUser20 = 44; 601 | 602 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 603 | /// 604 | /// MAV_COMP_ID_USER21 605 | const MavComponent mavCompIdUser21 = 45; 606 | 607 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 608 | /// 609 | /// MAV_COMP_ID_USER22 610 | const MavComponent mavCompIdUser22 = 46; 611 | 612 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 613 | /// 614 | /// MAV_COMP_ID_USER23 615 | const MavComponent mavCompIdUser23 = 47; 616 | 617 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 618 | /// 619 | /// MAV_COMP_ID_USER24 620 | const MavComponent mavCompIdUser24 = 48; 621 | 622 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 623 | /// 624 | /// MAV_COMP_ID_USER25 625 | const MavComponent mavCompIdUser25 = 49; 626 | 627 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 628 | /// 629 | /// MAV_COMP_ID_USER26 630 | const MavComponent mavCompIdUser26 = 50; 631 | 632 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 633 | /// 634 | /// MAV_COMP_ID_USER27 635 | const MavComponent mavCompIdUser27 = 51; 636 | 637 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 638 | /// 639 | /// MAV_COMP_ID_USER28 640 | const MavComponent mavCompIdUser28 = 52; 641 | 642 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 643 | /// 644 | /// MAV_COMP_ID_USER29 645 | const MavComponent mavCompIdUser29 = 53; 646 | 647 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 648 | /// 649 | /// MAV_COMP_ID_USER30 650 | const MavComponent mavCompIdUser30 = 54; 651 | 652 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 653 | /// 654 | /// MAV_COMP_ID_USER31 655 | const MavComponent mavCompIdUser31 = 55; 656 | 657 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 658 | /// 659 | /// MAV_COMP_ID_USER32 660 | const MavComponent mavCompIdUser32 = 56; 661 | 662 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 663 | /// 664 | /// MAV_COMP_ID_USER33 665 | const MavComponent mavCompIdUser33 = 57; 666 | 667 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 668 | /// 669 | /// MAV_COMP_ID_USER34 670 | const MavComponent mavCompIdUser34 = 58; 671 | 672 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 673 | /// 674 | /// MAV_COMP_ID_USER35 675 | const MavComponent mavCompIdUser35 = 59; 676 | 677 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 678 | /// 679 | /// MAV_COMP_ID_USER36 680 | const MavComponent mavCompIdUser36 = 60; 681 | 682 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 683 | /// 684 | /// MAV_COMP_ID_USER37 685 | const MavComponent mavCompIdUser37 = 61; 686 | 687 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 688 | /// 689 | /// MAV_COMP_ID_USER38 690 | const MavComponent mavCompIdUser38 = 62; 691 | 692 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 693 | /// 694 | /// MAV_COMP_ID_USER39 695 | const MavComponent mavCompIdUser39 = 63; 696 | 697 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 698 | /// 699 | /// MAV_COMP_ID_USER40 700 | const MavComponent mavCompIdUser40 = 64; 701 | 702 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 703 | /// 704 | /// MAV_COMP_ID_USER41 705 | const MavComponent mavCompIdUser41 = 65; 706 | 707 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 708 | /// 709 | /// MAV_COMP_ID_USER42 710 | const MavComponent mavCompIdUser42 = 66; 711 | 712 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 713 | /// 714 | /// MAV_COMP_ID_USER43 715 | const MavComponent mavCompIdUser43 = 67; 716 | 717 | /// Telemetry radio (e.g. SiK radio, or other component that emits RADIO_STATUS messages). 718 | /// 719 | /// MAV_COMP_ID_TELEMETRY_RADIO 720 | const MavComponent mavCompIdTelemetryRadio = 68; 721 | 722 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 723 | /// 724 | /// MAV_COMP_ID_USER45 725 | const MavComponent mavCompIdUser45 = 69; 726 | 727 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 728 | /// 729 | /// MAV_COMP_ID_USER46 730 | const MavComponent mavCompIdUser46 = 70; 731 | 732 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 733 | /// 734 | /// MAV_COMP_ID_USER47 735 | const MavComponent mavCompIdUser47 = 71; 736 | 737 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 738 | /// 739 | /// MAV_COMP_ID_USER48 740 | const MavComponent mavCompIdUser48 = 72; 741 | 742 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 743 | /// 744 | /// MAV_COMP_ID_USER49 745 | const MavComponent mavCompIdUser49 = 73; 746 | 747 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 748 | /// 749 | /// MAV_COMP_ID_USER50 750 | const MavComponent mavCompIdUser50 = 74; 751 | 752 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 753 | /// 754 | /// MAV_COMP_ID_USER51 755 | const MavComponent mavCompIdUser51 = 75; 756 | 757 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 758 | /// 759 | /// MAV_COMP_ID_USER52 760 | const MavComponent mavCompIdUser52 = 76; 761 | 762 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 763 | /// 764 | /// MAV_COMP_ID_USER53 765 | const MavComponent mavCompIdUser53 = 77; 766 | 767 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 768 | /// 769 | /// MAV_COMP_ID_USER54 770 | const MavComponent mavCompIdUser54 = 78; 771 | 772 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 773 | /// 774 | /// MAV_COMP_ID_USER55 775 | const MavComponent mavCompIdUser55 = 79; 776 | 777 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 778 | /// 779 | /// MAV_COMP_ID_USER56 780 | const MavComponent mavCompIdUser56 = 80; 781 | 782 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 783 | /// 784 | /// MAV_COMP_ID_USER57 785 | const MavComponent mavCompIdUser57 = 81; 786 | 787 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 788 | /// 789 | /// MAV_COMP_ID_USER58 790 | const MavComponent mavCompIdUser58 = 82; 791 | 792 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 793 | /// 794 | /// MAV_COMP_ID_USER59 795 | const MavComponent mavCompIdUser59 = 83; 796 | 797 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 798 | /// 799 | /// MAV_COMP_ID_USER60 800 | const MavComponent mavCompIdUser60 = 84; 801 | 802 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 803 | /// 804 | /// MAV_COMP_ID_USER61 805 | const MavComponent mavCompIdUser61 = 85; 806 | 807 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 808 | /// 809 | /// MAV_COMP_ID_USER62 810 | const MavComponent mavCompIdUser62 = 86; 811 | 812 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 813 | /// 814 | /// MAV_COMP_ID_USER63 815 | const MavComponent mavCompIdUser63 = 87; 816 | 817 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 818 | /// 819 | /// MAV_COMP_ID_USER64 820 | const MavComponent mavCompIdUser64 = 88; 821 | 822 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 823 | /// 824 | /// MAV_COMP_ID_USER65 825 | const MavComponent mavCompIdUser65 = 89; 826 | 827 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 828 | /// 829 | /// MAV_COMP_ID_USER66 830 | const MavComponent mavCompIdUser66 = 90; 831 | 832 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 833 | /// 834 | /// MAV_COMP_ID_USER67 835 | const MavComponent mavCompIdUser67 = 91; 836 | 837 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 838 | /// 839 | /// MAV_COMP_ID_USER68 840 | const MavComponent mavCompIdUser68 = 92; 841 | 842 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 843 | /// 844 | /// MAV_COMP_ID_USER69 845 | const MavComponent mavCompIdUser69 = 93; 846 | 847 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 848 | /// 849 | /// MAV_COMP_ID_USER70 850 | const MavComponent mavCompIdUser70 = 94; 851 | 852 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 853 | /// 854 | /// MAV_COMP_ID_USER71 855 | const MavComponent mavCompIdUser71 = 95; 856 | 857 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 858 | /// 859 | /// MAV_COMP_ID_USER72 860 | const MavComponent mavCompIdUser72 = 96; 861 | 862 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 863 | /// 864 | /// MAV_COMP_ID_USER73 865 | const MavComponent mavCompIdUser73 = 97; 866 | 867 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 868 | /// 869 | /// MAV_COMP_ID_USER74 870 | const MavComponent mavCompIdUser74 = 98; 871 | 872 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 873 | /// 874 | /// MAV_COMP_ID_USER75 875 | const MavComponent mavCompIdUser75 = 99; 876 | 877 | /// Camera #1. 878 | /// 879 | /// MAV_COMP_ID_CAMERA 880 | const MavComponent mavCompIdCamera = 100; 881 | 882 | /// Camera #2. 883 | /// 884 | /// MAV_COMP_ID_CAMERA2 885 | const MavComponent mavCompIdCamera2 = 101; 886 | 887 | /// Camera #3. 888 | /// 889 | /// MAV_COMP_ID_CAMERA3 890 | const MavComponent mavCompIdCamera3 = 102; 891 | 892 | /// Camera #4. 893 | /// 894 | /// MAV_COMP_ID_CAMERA4 895 | const MavComponent mavCompIdCamera4 = 103; 896 | 897 | /// Camera #5. 898 | /// 899 | /// MAV_COMP_ID_CAMERA5 900 | const MavComponent mavCompIdCamera5 = 104; 901 | 902 | /// Camera #6. 903 | /// 904 | /// MAV_COMP_ID_CAMERA6 905 | const MavComponent mavCompIdCamera6 = 105; 906 | 907 | /// Servo #1. 908 | /// 909 | /// MAV_COMP_ID_SERVO1 910 | const MavComponent mavCompIdServo1 = 140; 911 | 912 | /// Servo #2. 913 | /// 914 | /// MAV_COMP_ID_SERVO2 915 | const MavComponent mavCompIdServo2 = 141; 916 | 917 | /// Servo #3. 918 | /// 919 | /// MAV_COMP_ID_SERVO3 920 | const MavComponent mavCompIdServo3 = 142; 921 | 922 | /// Servo #4. 923 | /// 924 | /// MAV_COMP_ID_SERVO4 925 | const MavComponent mavCompIdServo4 = 143; 926 | 927 | /// Servo #5. 928 | /// 929 | /// MAV_COMP_ID_SERVO5 930 | const MavComponent mavCompIdServo5 = 144; 931 | 932 | /// Servo #6. 933 | /// 934 | /// MAV_COMP_ID_SERVO6 935 | const MavComponent mavCompIdServo6 = 145; 936 | 937 | /// Servo #7. 938 | /// 939 | /// MAV_COMP_ID_SERVO7 940 | const MavComponent mavCompIdServo7 = 146; 941 | 942 | /// Servo #8. 943 | /// 944 | /// MAV_COMP_ID_SERVO8 945 | const MavComponent mavCompIdServo8 = 147; 946 | 947 | /// Servo #9. 948 | /// 949 | /// MAV_COMP_ID_SERVO9 950 | const MavComponent mavCompIdServo9 = 148; 951 | 952 | /// Servo #10. 953 | /// 954 | /// MAV_COMP_ID_SERVO10 955 | const MavComponent mavCompIdServo10 = 149; 956 | 957 | /// Servo #11. 958 | /// 959 | /// MAV_COMP_ID_SERVO11 960 | const MavComponent mavCompIdServo11 = 150; 961 | 962 | /// Servo #12. 963 | /// 964 | /// MAV_COMP_ID_SERVO12 965 | const MavComponent mavCompIdServo12 = 151; 966 | 967 | /// Servo #13. 968 | /// 969 | /// MAV_COMP_ID_SERVO13 970 | const MavComponent mavCompIdServo13 = 152; 971 | 972 | /// Servo #14. 973 | /// 974 | /// MAV_COMP_ID_SERVO14 975 | const MavComponent mavCompIdServo14 = 153; 976 | 977 | /// Gimbal #1. 978 | /// 979 | /// MAV_COMP_ID_GIMBAL 980 | const MavComponent mavCompIdGimbal = 154; 981 | 982 | /// Logging component. 983 | /// 984 | /// MAV_COMP_ID_LOG 985 | const MavComponent mavCompIdLog = 155; 986 | 987 | /// Automatic Dependent Surveillance-Broadcast (ADS-B) component. 988 | /// 989 | /// MAV_COMP_ID_ADSB 990 | const MavComponent mavCompIdAdsb = 156; 991 | 992 | /// On Screen Display (OSD) devices for video links. 993 | /// 994 | /// MAV_COMP_ID_OSD 995 | const MavComponent mavCompIdOsd = 157; 996 | 997 | /// Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter microservice. 998 | /// 999 | /// MAV_COMP_ID_PERIPHERAL 1000 | const MavComponent mavCompIdPeripheral = 158; 1001 | 1002 | /// Gimbal ID for QX1. 1003 | /// 1004 | /// MAV_COMP_ID_QX1_GIMBAL 1005 | @Deprecated( 1006 | "Replaced by [MAV_COMP_ID_GIMBAL] since 2018-11. All gimbals should use MAV_COMP_ID_GIMBAL.") 1007 | const MavComponent mavCompIdQx1Gimbal = 159; 1008 | 1009 | /// FLARM collision alert component. 1010 | /// 1011 | /// MAV_COMP_ID_FLARM 1012 | const MavComponent mavCompIdFlarm = 160; 1013 | 1014 | /// Parachute component. 1015 | /// 1016 | /// MAV_COMP_ID_PARACHUTE 1017 | const MavComponent mavCompIdParachute = 161; 1018 | 1019 | /// Winch component. 1020 | /// 1021 | /// MAV_COMP_ID_WINCH 1022 | const MavComponent mavCompIdWinch = 169; 1023 | 1024 | /// Gimbal #2. 1025 | /// 1026 | /// MAV_COMP_ID_GIMBAL2 1027 | const MavComponent mavCompIdGimbal2 = 171; 1028 | 1029 | /// Gimbal #3. 1030 | /// 1031 | /// MAV_COMP_ID_GIMBAL3 1032 | const MavComponent mavCompIdGimbal3 = 172; 1033 | 1034 | /// Gimbal #4 1035 | /// 1036 | /// MAV_COMP_ID_GIMBAL4 1037 | const MavComponent mavCompIdGimbal4 = 173; 1038 | 1039 | /// Gimbal #5. 1040 | /// 1041 | /// MAV_COMP_ID_GIMBAL5 1042 | const MavComponent mavCompIdGimbal5 = 174; 1043 | 1044 | /// Gimbal #6. 1045 | /// 1046 | /// MAV_COMP_ID_GIMBAL6 1047 | const MavComponent mavCompIdGimbal6 = 175; 1048 | 1049 | /// Battery #1. 1050 | /// 1051 | /// MAV_COMP_ID_BATTERY 1052 | const MavComponent mavCompIdBattery = 180; 1053 | 1054 | /// Battery #2. 1055 | /// 1056 | /// MAV_COMP_ID_BATTERY2 1057 | const MavComponent mavCompIdBattery2 = 181; 1058 | 1059 | /// CAN over MAVLink client. 1060 | /// 1061 | /// MAV_COMP_ID_MAVCAN 1062 | const MavComponent mavCompIdMavcan = 189; 1063 | 1064 | /// Component that can generate/supply a mission flight plan (e.g. GCS or developer API). 1065 | /// 1066 | /// MAV_COMP_ID_MISSIONPLANNER 1067 | const MavComponent mavCompIdMissionplanner = 190; 1068 | 1069 | /// Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. 1070 | /// 1071 | /// MAV_COMP_ID_ONBOARD_COMPUTER 1072 | const MavComponent mavCompIdOnboardComputer = 191; 1073 | 1074 | /// Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. 1075 | /// 1076 | /// MAV_COMP_ID_ONBOARD_COMPUTER2 1077 | const MavComponent mavCompIdOnboardComputer2 = 192; 1078 | 1079 | /// Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. 1080 | /// 1081 | /// MAV_COMP_ID_ONBOARD_COMPUTER3 1082 | const MavComponent mavCompIdOnboardComputer3 = 193; 1083 | 1084 | /// Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. 1085 | /// 1086 | /// MAV_COMP_ID_ONBOARD_COMPUTER4 1087 | const MavComponent mavCompIdOnboardComputer4 = 194; 1088 | 1089 | /// Component that finds an optimal path between points based on a certain constraint (e.g. minimum snap, shortest path, cost, etc.). 1090 | /// 1091 | /// MAV_COMP_ID_PATHPLANNER 1092 | const MavComponent mavCompIdPathplanner = 195; 1093 | 1094 | /// Component that plans a collision free path between two points. 1095 | /// 1096 | /// MAV_COMP_ID_OBSTACLE_AVOIDANCE 1097 | const MavComponent mavCompIdObstacleAvoidance = 196; 1098 | 1099 | /// Component that provides position estimates using VIO techniques. 1100 | /// 1101 | /// MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY 1102 | const MavComponent mavCompIdVisualInertialOdometry = 197; 1103 | 1104 | /// Component that manages pairing of vehicle and GCS. 1105 | /// 1106 | /// MAV_COMP_ID_PAIRING_MANAGER 1107 | const MavComponent mavCompIdPairingManager = 198; 1108 | 1109 | /// Inertial Measurement Unit (IMU) #1. 1110 | /// 1111 | /// MAV_COMP_ID_IMU 1112 | const MavComponent mavCompIdImu = 200; 1113 | 1114 | /// Inertial Measurement Unit (IMU) #2. 1115 | /// 1116 | /// MAV_COMP_ID_IMU_2 1117 | const MavComponent mavCompIdImu2 = 201; 1118 | 1119 | /// Inertial Measurement Unit (IMU) #3. 1120 | /// 1121 | /// MAV_COMP_ID_IMU_3 1122 | const MavComponent mavCompIdImu3 = 202; 1123 | 1124 | /// GPS #1. 1125 | /// 1126 | /// MAV_COMP_ID_GPS 1127 | const MavComponent mavCompIdGps = 220; 1128 | 1129 | /// GPS #2. 1130 | /// 1131 | /// MAV_COMP_ID_GPS2 1132 | const MavComponent mavCompIdGps2 = 221; 1133 | 1134 | /// Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet). 1135 | /// 1136 | /// MAV_COMP_ID_ODID_TXRX_1 1137 | const MavComponent mavCompIdOdidTxrx1 = 236; 1138 | 1139 | /// Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet). 1140 | /// 1141 | /// MAV_COMP_ID_ODID_TXRX_2 1142 | const MavComponent mavCompIdOdidTxrx2 = 237; 1143 | 1144 | /// Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet). 1145 | /// 1146 | /// MAV_COMP_ID_ODID_TXRX_3 1147 | const MavComponent mavCompIdOdidTxrx3 = 238; 1148 | 1149 | /// Component to bridge MAVLink to UDP (i.e. from a UART). 1150 | /// 1151 | /// MAV_COMP_ID_UDP_BRIDGE 1152 | const MavComponent mavCompIdUdpBridge = 240; 1153 | 1154 | /// Component to bridge to UART (i.e. from UDP). 1155 | /// 1156 | /// MAV_COMP_ID_UART_BRIDGE 1157 | const MavComponent mavCompIdUartBridge = 241; 1158 | 1159 | /// Component handling TUNNEL messages (e.g. vendor specific GUI of a component). 1160 | /// 1161 | /// MAV_COMP_ID_TUNNEL_NODE 1162 | const MavComponent mavCompIdTunnelNode = 242; 1163 | 1164 | /// Illuminator 1165 | /// 1166 | /// MAV_COMP_ID_ILLUMINATOR 1167 | const MavComponent mavCompIdIlluminator = 243; 1168 | 1169 | /// Deprecated, don't use. Component for handling system messages (e.g. to ARM, takeoff, etc.). 1170 | /// 1171 | /// MAV_COMP_ID_SYSTEM_CONTROL 1172 | @Deprecated( 1173 | "Replaced by [MAV_COMP_ID_ALL] since 2018-11. System control does not require a separate component ID. Instead, system commands should be sent with target_component=MAV_COMP_ID_ALL allowing the target component to use any appropriate component id.") 1174 | const MavComponent mavCompIdSystemControl = 250; 1175 | 1176 | /// The heartbeat message shows that a system or component is present and responding. The type and autopilot fields (along with the message component id), allow the receiving system to treat further messages from this system appropriately (e.g. by laying out the user interface based on the autopilot). This microservice is documented at https://mavlink.io/en/services/heartbeat.html 1177 | /// 1178 | /// HEARTBEAT 1179 | class Heartbeat implements MavlinkMessage { 1180 | static const int _mavlinkMessageId = 0; 1181 | 1182 | static const int _mavlinkCrcExtra = 50; 1183 | 1184 | static const int mavlinkEncodedLength = 9; 1185 | 1186 | @override 1187 | int get mavlinkMessageId => _mavlinkMessageId; 1188 | 1189 | @override 1190 | int get mavlinkCrcExtra => _mavlinkCrcExtra; 1191 | 1192 | /// A bitfield for use for autopilot-specific flags 1193 | /// 1194 | /// MAVLink type: uint32_t 1195 | /// 1196 | /// custom_mode 1197 | final uint32_t customMode; 1198 | 1199 | /// Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type. 1200 | /// 1201 | /// MAVLink type: uint8_t 1202 | /// 1203 | /// enum: [MavType] 1204 | /// 1205 | /// type 1206 | final MavType type; 1207 | 1208 | /// Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers. 1209 | /// 1210 | /// MAVLink type: uint8_t 1211 | /// 1212 | /// enum: [MavAutopilot] 1213 | /// 1214 | /// autopilot 1215 | final MavAutopilot autopilot; 1216 | 1217 | /// System mode bitmap. 1218 | /// 1219 | /// MAVLink type: uint8_t 1220 | /// 1221 | /// enum: [MavModeFlag] 1222 | /// 1223 | /// base_mode 1224 | final MavModeFlag baseMode; 1225 | 1226 | /// System status flag. 1227 | /// 1228 | /// MAVLink type: uint8_t 1229 | /// 1230 | /// enum: [MavState] 1231 | /// 1232 | /// system_status 1233 | final MavState systemStatus; 1234 | 1235 | /// MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version 1236 | /// 1237 | /// MAVLink type: uint8_t 1238 | /// 1239 | /// mavlink_version 1240 | final uint8_t mavlinkVersion; 1241 | 1242 | Heartbeat({ 1243 | required this.customMode, 1244 | required this.type, 1245 | required this.autopilot, 1246 | required this.baseMode, 1247 | required this.systemStatus, 1248 | required this.mavlinkVersion, 1249 | }); 1250 | 1251 | Heartbeat copyWith({ 1252 | uint32_t? customMode, 1253 | MavType? type, 1254 | MavAutopilot? autopilot, 1255 | MavModeFlag? baseMode, 1256 | MavState? systemStatus, 1257 | uint8_t? mavlinkVersion, 1258 | }) { 1259 | return Heartbeat( 1260 | customMode: customMode ?? this.customMode, 1261 | type: type ?? this.type, 1262 | autopilot: autopilot ?? this.autopilot, 1263 | baseMode: baseMode ?? this.baseMode, 1264 | systemStatus: systemStatus ?? this.systemStatus, 1265 | mavlinkVersion: mavlinkVersion ?? this.mavlinkVersion, 1266 | ); 1267 | } 1268 | 1269 | factory Heartbeat.parse(ByteData data_) { 1270 | if (data_.lengthInBytes < Heartbeat.mavlinkEncodedLength) { 1271 | var len = Heartbeat.mavlinkEncodedLength - data_.lengthInBytes; 1272 | var d = data_.buffer.asUint8List().sublist(0, data_.lengthInBytes) + 1273 | List.filled(len, 0); 1274 | data_ = Uint8List.fromList(d).buffer.asByteData(); 1275 | } 1276 | var customMode = data_.getUint32(0, Endian.little); 1277 | var type = data_.getUint8(4); 1278 | var autopilot = data_.getUint8(5); 1279 | var baseMode = data_.getUint8(6); 1280 | var systemStatus = data_.getUint8(7); 1281 | var mavlinkVersion = data_.getUint8(8); 1282 | 1283 | return Heartbeat( 1284 | customMode: customMode, 1285 | type: type, 1286 | autopilot: autopilot, 1287 | baseMode: baseMode, 1288 | systemStatus: systemStatus, 1289 | mavlinkVersion: mavlinkVersion); 1290 | } 1291 | 1292 | @override 1293 | ByteData serialize() { 1294 | var data_ = ByteData(mavlinkEncodedLength); 1295 | data_.setUint32(0, customMode, Endian.little); 1296 | data_.setUint8(4, type); 1297 | data_.setUint8(5, autopilot); 1298 | data_.setUint8(6, baseMode); 1299 | data_.setUint8(7, systemStatus); 1300 | data_.setUint8(8, mavlinkVersion); 1301 | return data_; 1302 | } 1303 | } 1304 | 1305 | /// Version and capability of protocol version. This message can be requested with MAV_CMD_REQUEST_MESSAGE and is used as part of the handshaking to establish which MAVLink version should be used on the network. Every node should respond to a request for PROTOCOL_VERSION to enable the handshaking. Library implementers should consider adding this into the default decoding state machine to allow the protocol core to respond directly. 1306 | /// 1307 | /// PROTOCOL_VERSION 1308 | class ProtocolVersion implements MavlinkMessage { 1309 | static const int _mavlinkMessageId = 300; 1310 | 1311 | static const int _mavlinkCrcExtra = 217; 1312 | 1313 | static const int mavlinkEncodedLength = 22; 1314 | 1315 | @override 1316 | int get mavlinkMessageId => _mavlinkMessageId; 1317 | 1318 | @override 1319 | int get mavlinkCrcExtra => _mavlinkCrcExtra; 1320 | 1321 | /// Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc. 1322 | /// 1323 | /// MAVLink type: uint16_t 1324 | /// 1325 | /// version 1326 | final uint16_t version; 1327 | 1328 | /// Minimum MAVLink version supported 1329 | /// 1330 | /// MAVLink type: uint16_t 1331 | /// 1332 | /// min_version 1333 | final uint16_t minVersion; 1334 | 1335 | /// Maximum MAVLink version supported (set to the same value as version by default) 1336 | /// 1337 | /// MAVLink type: uint16_t 1338 | /// 1339 | /// max_version 1340 | final uint16_t maxVersion; 1341 | 1342 | /// The first 8 bytes (not characters printed in hex!) of the git hash. 1343 | /// 1344 | /// MAVLink type: uint8_t[8] 1345 | /// 1346 | /// spec_version_hash 1347 | final List specVersionHash; 1348 | 1349 | /// The first 8 bytes (not characters printed in hex!) of the git hash. 1350 | /// 1351 | /// MAVLink type: uint8_t[8] 1352 | /// 1353 | /// library_version_hash 1354 | final List libraryVersionHash; 1355 | 1356 | ProtocolVersion({ 1357 | required this.version, 1358 | required this.minVersion, 1359 | required this.maxVersion, 1360 | required this.specVersionHash, 1361 | required this.libraryVersionHash, 1362 | }); 1363 | 1364 | ProtocolVersion copyWith({ 1365 | uint16_t? version, 1366 | uint16_t? minVersion, 1367 | uint16_t? maxVersion, 1368 | List? specVersionHash, 1369 | List? libraryVersionHash, 1370 | }) { 1371 | return ProtocolVersion( 1372 | version: version ?? this.version, 1373 | minVersion: minVersion ?? this.minVersion, 1374 | maxVersion: maxVersion ?? this.maxVersion, 1375 | specVersionHash: specVersionHash ?? this.specVersionHash, 1376 | libraryVersionHash: libraryVersionHash ?? this.libraryVersionHash, 1377 | ); 1378 | } 1379 | 1380 | factory ProtocolVersion.parse(ByteData data_) { 1381 | if (data_.lengthInBytes < ProtocolVersion.mavlinkEncodedLength) { 1382 | var len = ProtocolVersion.mavlinkEncodedLength - data_.lengthInBytes; 1383 | var d = data_.buffer.asUint8List().sublist(0, data_.lengthInBytes) + 1384 | List.filled(len, 0); 1385 | data_ = Uint8List.fromList(d).buffer.asByteData(); 1386 | } 1387 | var version = data_.getUint16(0, Endian.little); 1388 | var minVersion = data_.getUint16(2, Endian.little); 1389 | var maxVersion = data_.getUint16(4, Endian.little); 1390 | var specVersionHash = MavlinkMessage.asUint8List(data_, 6, 8); 1391 | var libraryVersionHash = MavlinkMessage.asUint8List(data_, 14, 8); 1392 | 1393 | return ProtocolVersion( 1394 | version: version, 1395 | minVersion: minVersion, 1396 | maxVersion: maxVersion, 1397 | specVersionHash: specVersionHash, 1398 | libraryVersionHash: libraryVersionHash); 1399 | } 1400 | 1401 | @override 1402 | ByteData serialize() { 1403 | var data_ = ByteData(mavlinkEncodedLength); 1404 | data_.setUint16(0, version, Endian.little); 1405 | data_.setUint16(2, minVersion, Endian.little); 1406 | data_.setUint16(4, maxVersion, Endian.little); 1407 | MavlinkMessage.setUint8List(data_, 6, specVersionHash); 1408 | MavlinkMessage.setUint8List(data_, 14, libraryVersionHash); 1409 | return data_; 1410 | } 1411 | } 1412 | 1413 | class MavlinkDialectMinimal implements MavlinkDialect { 1414 | static const int mavlinkVersion = 3; 1415 | 1416 | @override 1417 | int get version => mavlinkVersion; 1418 | 1419 | @override 1420 | MavlinkMessage? parse(int messageID, ByteData data) { 1421 | switch (messageID) { 1422 | case 0: 1423 | return Heartbeat.parse(data); 1424 | case 300: 1425 | return ProtocolVersion.parse(data); 1426 | default: 1427 | return null; 1428 | } 1429 | } 1430 | 1431 | @override 1432 | int crcExtra(int messageID) { 1433 | switch (messageID) { 1434 | case 0: 1435 | return Heartbeat._mavlinkCrcExtra; 1436 | case 300: 1437 | return ProtocolVersion._mavlinkCrcExtra; 1438 | default: 1439 | return -1; 1440 | } 1441 | } 1442 | } 1443 | -------------------------------------------------------------------------------- /lib/dialects/standard.dart: -------------------------------------------------------------------------------- 1 | import 'dart:typed_data'; 2 | import 'package:dart_mavlink/mavlink_dialect.dart'; 3 | import 'package:dart_mavlink/mavlink_message.dart'; 4 | import 'package:dart_mavlink/types.dart'; 5 | 6 | /// Micro air vehicle / autopilot classes. This identifies the individual model. 7 | /// 8 | /// MAV_AUTOPILOT 9 | typedef MavAutopilot = int; 10 | 11 | /// Generic autopilot, full support for everything 12 | /// 13 | /// MAV_AUTOPILOT_GENERIC 14 | const MavAutopilot mavAutopilotGeneric = 0; 15 | 16 | /// Reserved for future use. 17 | /// 18 | /// MAV_AUTOPILOT_RESERVED 19 | const MavAutopilot mavAutopilotReserved = 1; 20 | 21 | /// SLUGS autopilot, http://slugsuav.soe.ucsc.edu 22 | /// 23 | /// MAV_AUTOPILOT_SLUGS 24 | const MavAutopilot mavAutopilotSlugs = 2; 25 | 26 | /// ArduPilot - Plane/Copter/Rover/Sub/Tracker, https://ardupilot.org 27 | /// 28 | /// MAV_AUTOPILOT_ARDUPILOTMEGA 29 | const MavAutopilot mavAutopilotArdupilotmega = 3; 30 | 31 | /// OpenPilot, http://openpilot.org 32 | /// 33 | /// MAV_AUTOPILOT_OPENPILOT 34 | const MavAutopilot mavAutopilotOpenpilot = 4; 35 | 36 | /// Generic autopilot only supporting simple waypoints 37 | /// 38 | /// MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY 39 | const MavAutopilot mavAutopilotGenericWaypointsOnly = 5; 40 | 41 | /// Generic autopilot supporting waypoints and other simple navigation commands 42 | /// 43 | /// MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY 44 | const MavAutopilot mavAutopilotGenericWaypointsAndSimpleNavigationOnly = 6; 45 | 46 | /// Generic autopilot supporting the full mission command set 47 | /// 48 | /// MAV_AUTOPILOT_GENERIC_MISSION_FULL 49 | const MavAutopilot mavAutopilotGenericMissionFull = 7; 50 | 51 | /// No valid autopilot, e.g. a GCS or other MAVLink component 52 | /// 53 | /// MAV_AUTOPILOT_INVALID 54 | const MavAutopilot mavAutopilotInvalid = 8; 55 | 56 | /// PPZ UAV - http://nongnu.org/paparazzi 57 | /// 58 | /// MAV_AUTOPILOT_PPZ 59 | const MavAutopilot mavAutopilotPpz = 9; 60 | 61 | /// UAV Dev Board 62 | /// 63 | /// MAV_AUTOPILOT_UDB 64 | const MavAutopilot mavAutopilotUdb = 10; 65 | 66 | /// FlexiPilot 67 | /// 68 | /// MAV_AUTOPILOT_FP 69 | const MavAutopilot mavAutopilotFp = 11; 70 | 71 | /// PX4 Autopilot - http://px4.io/ 72 | /// 73 | /// MAV_AUTOPILOT_PX4 74 | const MavAutopilot mavAutopilotPx4 = 12; 75 | 76 | /// SMACCMPilot - http://smaccmpilot.org 77 | /// 78 | /// MAV_AUTOPILOT_SMACCMPILOT 79 | const MavAutopilot mavAutopilotSmaccmpilot = 13; 80 | 81 | /// AutoQuad -- http://autoquad.org 82 | /// 83 | /// MAV_AUTOPILOT_AUTOQUAD 84 | const MavAutopilot mavAutopilotAutoquad = 14; 85 | 86 | /// Armazila -- http://armazila.com 87 | /// 88 | /// MAV_AUTOPILOT_ARMAZILA 89 | const MavAutopilot mavAutopilotArmazila = 15; 90 | 91 | /// Aerob -- http://aerob.ru 92 | /// 93 | /// MAV_AUTOPILOT_AEROB 94 | const MavAutopilot mavAutopilotAerob = 16; 95 | 96 | /// ASLUAV autopilot -- http://www.asl.ethz.ch 97 | /// 98 | /// MAV_AUTOPILOT_ASLUAV 99 | const MavAutopilot mavAutopilotAsluav = 17; 100 | 101 | /// SmartAP Autopilot - http://sky-drones.com 102 | /// 103 | /// MAV_AUTOPILOT_SMARTAP 104 | const MavAutopilot mavAutopilotSmartap = 18; 105 | 106 | /// AirRails - http://uaventure.com 107 | /// 108 | /// MAV_AUTOPILOT_AIRRAILS 109 | const MavAutopilot mavAutopilotAirrails = 19; 110 | 111 | /// Fusion Reflex - https://fusion.engineering 112 | /// 113 | /// MAV_AUTOPILOT_REFLEX 114 | const MavAutopilot mavAutopilotReflex = 20; 115 | 116 | /// MAVLINK component type reported in HEARTBEAT message. Flight controllers must report the type of the vehicle on which they are mounted (e.g. MAV_TYPE_OCTOROTOR). All other components must report a value appropriate for their type (e.g. a camera must use MAV_TYPE_CAMERA). 117 | /// 118 | /// MAV_TYPE 119 | typedef MavType = int; 120 | 121 | /// Generic micro air vehicle 122 | /// 123 | /// MAV_TYPE_GENERIC 124 | const MavType mavTypeGeneric = 0; 125 | 126 | /// Fixed wing aircraft. 127 | /// 128 | /// MAV_TYPE_FIXED_WING 129 | const MavType mavTypeFixedWing = 1; 130 | 131 | /// Quadrotor 132 | /// 133 | /// MAV_TYPE_QUADROTOR 134 | const MavType mavTypeQuadrotor = 2; 135 | 136 | /// Coaxial helicopter 137 | /// 138 | /// MAV_TYPE_COAXIAL 139 | const MavType mavTypeCoaxial = 3; 140 | 141 | /// Normal helicopter with tail rotor. 142 | /// 143 | /// MAV_TYPE_HELICOPTER 144 | const MavType mavTypeHelicopter = 4; 145 | 146 | /// Ground installation 147 | /// 148 | /// MAV_TYPE_ANTENNA_TRACKER 149 | const MavType mavTypeAntennaTracker = 5; 150 | 151 | /// Operator control unit / ground control station 152 | /// 153 | /// MAV_TYPE_GCS 154 | const MavType mavTypeGcs = 6; 155 | 156 | /// Airship, controlled 157 | /// 158 | /// MAV_TYPE_AIRSHIP 159 | const MavType mavTypeAirship = 7; 160 | 161 | /// Free balloon, uncontrolled 162 | /// 163 | /// MAV_TYPE_FREE_BALLOON 164 | const MavType mavTypeFreeBalloon = 8; 165 | 166 | /// Rocket 167 | /// 168 | /// MAV_TYPE_ROCKET 169 | const MavType mavTypeRocket = 9; 170 | 171 | /// Ground rover 172 | /// 173 | /// MAV_TYPE_GROUND_ROVER 174 | const MavType mavTypeGroundRover = 10; 175 | 176 | /// Surface vessel, boat, ship 177 | /// 178 | /// MAV_TYPE_SURFACE_BOAT 179 | const MavType mavTypeSurfaceBoat = 11; 180 | 181 | /// Submarine 182 | /// 183 | /// MAV_TYPE_SUBMARINE 184 | const MavType mavTypeSubmarine = 12; 185 | 186 | /// Hexarotor 187 | /// 188 | /// MAV_TYPE_HEXAROTOR 189 | const MavType mavTypeHexarotor = 13; 190 | 191 | /// Octorotor 192 | /// 193 | /// MAV_TYPE_OCTOROTOR 194 | const MavType mavTypeOctorotor = 14; 195 | 196 | /// Tricopter 197 | /// 198 | /// MAV_TYPE_TRICOPTER 199 | const MavType mavTypeTricopter = 15; 200 | 201 | /// Flapping wing 202 | /// 203 | /// MAV_TYPE_FLAPPING_WING 204 | const MavType mavTypeFlappingWing = 16; 205 | 206 | /// Kite 207 | /// 208 | /// MAV_TYPE_KITE 209 | const MavType mavTypeKite = 17; 210 | 211 | /// Onboard companion controller 212 | /// 213 | /// MAV_TYPE_ONBOARD_CONTROLLER 214 | const MavType mavTypeOnboardController = 18; 215 | 216 | /// Two-rotor Tailsitter VTOL that additionally uses control surfaces in vertical operation. Note, value previously named MAV_TYPE_VTOL_DUOROTOR. 217 | /// 218 | /// MAV_TYPE_VTOL_TAILSITTER_DUOROTOR 219 | const MavType mavTypeVtolTailsitterDuorotor = 19; 220 | 221 | /// Quad-rotor Tailsitter VTOL using a V-shaped quad config in vertical operation. Note: value previously named MAV_TYPE_VTOL_QUADROTOR. 222 | /// 223 | /// MAV_TYPE_VTOL_TAILSITTER_QUADROTOR 224 | const MavType mavTypeVtolTailsitterQuadrotor = 20; 225 | 226 | /// Tiltrotor VTOL. Fuselage and wings stay (nominally) horizontal in all flight phases. It able to tilt (some) rotors to provide thrust in cruise flight. 227 | /// 228 | /// MAV_TYPE_VTOL_TILTROTOR 229 | const MavType mavTypeVtolTiltrotor = 21; 230 | 231 | /// VTOL with separate fixed rotors for hover and cruise flight. Fuselage and wings stay (nominally) horizontal in all flight phases. 232 | /// 233 | /// MAV_TYPE_VTOL_FIXEDROTOR 234 | const MavType mavTypeVtolFixedrotor = 22; 235 | 236 | /// Tailsitter VTOL. Fuselage and wings orientation changes depending on flight phase: vertical for hover, horizontal for cruise. Use more specific VTOL MAV_TYPE_VTOL_TAILSITTER_DUOROTOR or MAV_TYPE_VTOL_TAILSITTER_QUADROTOR if appropriate. 237 | /// 238 | /// MAV_TYPE_VTOL_TAILSITTER 239 | const MavType mavTypeVtolTailsitter = 23; 240 | 241 | /// Tiltwing VTOL. Fuselage stays horizontal in all flight phases. The whole wing, along with any attached engine, can tilt between vertical and horizontal mode. 242 | /// 243 | /// MAV_TYPE_VTOL_TILTWING 244 | const MavType mavTypeVtolTiltwing = 24; 245 | 246 | /// VTOL reserved 5 247 | /// 248 | /// MAV_TYPE_VTOL_RESERVED5 249 | const MavType mavTypeVtolReserved5 = 25; 250 | 251 | /// Gimbal 252 | /// 253 | /// MAV_TYPE_GIMBAL 254 | const MavType mavTypeGimbal = 26; 255 | 256 | /// ADSB system 257 | /// 258 | /// MAV_TYPE_ADSB 259 | const MavType mavTypeAdsb = 27; 260 | 261 | /// Steerable, nonrigid airfoil 262 | /// 263 | /// MAV_TYPE_PARAFOIL 264 | const MavType mavTypeParafoil = 28; 265 | 266 | /// Dodecarotor 267 | /// 268 | /// MAV_TYPE_DODECAROTOR 269 | const MavType mavTypeDodecarotor = 29; 270 | 271 | /// Camera 272 | /// 273 | /// MAV_TYPE_CAMERA 274 | const MavType mavTypeCamera = 30; 275 | 276 | /// Charging station 277 | /// 278 | /// MAV_TYPE_CHARGING_STATION 279 | const MavType mavTypeChargingStation = 31; 280 | 281 | /// FLARM collision avoidance system 282 | /// 283 | /// MAV_TYPE_FLARM 284 | const MavType mavTypeFlarm = 32; 285 | 286 | /// Servo 287 | /// 288 | /// MAV_TYPE_SERVO 289 | const MavType mavTypeServo = 33; 290 | 291 | /// Open Drone ID. See https://mavlink.io/en/services/opendroneid.html. 292 | /// 293 | /// MAV_TYPE_ODID 294 | const MavType mavTypeOdid = 34; 295 | 296 | /// Decarotor 297 | /// 298 | /// MAV_TYPE_DECAROTOR 299 | const MavType mavTypeDecarotor = 35; 300 | 301 | /// Battery 302 | /// 303 | /// MAV_TYPE_BATTERY 304 | const MavType mavTypeBattery = 36; 305 | 306 | /// Parachute 307 | /// 308 | /// MAV_TYPE_PARACHUTE 309 | const MavType mavTypeParachute = 37; 310 | 311 | /// Log 312 | /// 313 | /// MAV_TYPE_LOG 314 | const MavType mavTypeLog = 38; 315 | 316 | /// OSD 317 | /// 318 | /// MAV_TYPE_OSD 319 | const MavType mavTypeOsd = 39; 320 | 321 | /// IMU 322 | /// 323 | /// MAV_TYPE_IMU 324 | const MavType mavTypeImu = 40; 325 | 326 | /// GPS 327 | /// 328 | /// MAV_TYPE_GPS 329 | const MavType mavTypeGps = 41; 330 | 331 | /// Winch 332 | /// 333 | /// MAV_TYPE_WINCH 334 | const MavType mavTypeWinch = 42; 335 | 336 | /// Generic multirotor that does not fit into a specific type or whose type is unknown 337 | /// 338 | /// MAV_TYPE_GENERIC_MULTIROTOR 339 | const MavType mavTypeGenericMultirotor = 43; 340 | 341 | /// Illuminator. An illuminator is a light source that is used for lighting up dark areas external to the sytstem: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light). 342 | /// 343 | /// MAV_TYPE_ILLUMINATOR 344 | const MavType mavTypeIlluminator = 44; 345 | 346 | /// These flags encode the MAV mode. 347 | /// 348 | /// MAV_MODE_FLAG 349 | typedef MavModeFlag = int; 350 | 351 | /// 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. Additional note: this flag is to be ignore when sent in the command MAV_CMD_DO_SET_MODE and MAV_CMD_COMPONENT_ARM_DISARM shall be used instead. The flag can still be used to report the armed state. 352 | /// 353 | /// MAV_MODE_FLAG_SAFETY_ARMED 354 | const MavModeFlag mavModeFlagSafetyArmed = 128; 355 | 356 | /// 0b01000000 remote control input is enabled. 357 | /// 358 | /// MAV_MODE_FLAG_MANUAL_INPUT_ENABLED 359 | const MavModeFlag mavModeFlagManualInputEnabled = 64; 360 | 361 | /// 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. 362 | /// 363 | /// MAV_MODE_FLAG_HIL_ENABLED 364 | const MavModeFlag mavModeFlagHilEnabled = 32; 365 | 366 | /// 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. 367 | /// 368 | /// MAV_MODE_FLAG_STABILIZE_ENABLED 369 | const MavModeFlag mavModeFlagStabilizeEnabled = 16; 370 | 371 | /// 0b00001000 guided mode enabled, system flies waypoints / mission items. 372 | /// 373 | /// MAV_MODE_FLAG_GUIDED_ENABLED 374 | const MavModeFlag mavModeFlagGuidedEnabled = 8; 375 | 376 | /// 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. 377 | /// 378 | /// MAV_MODE_FLAG_AUTO_ENABLED 379 | const MavModeFlag mavModeFlagAutoEnabled = 4; 380 | 381 | /// 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. 382 | /// 383 | /// MAV_MODE_FLAG_TEST_ENABLED 384 | const MavModeFlag mavModeFlagTestEnabled = 2; 385 | 386 | /// 0b00000001 Reserved for future use. 387 | /// 388 | /// MAV_MODE_FLAG_CUSTOM_MODE_ENABLED 389 | const MavModeFlag mavModeFlagCustomModeEnabled = 1; 390 | 391 | /// These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. 392 | /// 393 | /// MAV_MODE_FLAG_DECODE_POSITION 394 | typedef MavModeFlagDecodePosition = int; 395 | 396 | /// First bit: 10000000 397 | /// 398 | /// MAV_MODE_FLAG_DECODE_POSITION_SAFETY 399 | const MavModeFlagDecodePosition mavModeFlagDecodePositionSafety = 128; 400 | 401 | /// Second bit: 01000000 402 | /// 403 | /// MAV_MODE_FLAG_DECODE_POSITION_MANUAL 404 | const MavModeFlagDecodePosition mavModeFlagDecodePositionManual = 64; 405 | 406 | /// Third bit: 00100000 407 | /// 408 | /// MAV_MODE_FLAG_DECODE_POSITION_HIL 409 | const MavModeFlagDecodePosition mavModeFlagDecodePositionHil = 32; 410 | 411 | /// Fourth bit: 00010000 412 | /// 413 | /// MAV_MODE_FLAG_DECODE_POSITION_STABILIZE 414 | const MavModeFlagDecodePosition mavModeFlagDecodePositionStabilize = 16; 415 | 416 | /// Fifth bit: 00001000 417 | /// 418 | /// MAV_MODE_FLAG_DECODE_POSITION_GUIDED 419 | const MavModeFlagDecodePosition mavModeFlagDecodePositionGuided = 8; 420 | 421 | /// Sixth bit: 00000100 422 | /// 423 | /// MAV_MODE_FLAG_DECODE_POSITION_AUTO 424 | const MavModeFlagDecodePosition mavModeFlagDecodePositionAuto = 4; 425 | 426 | /// Seventh bit: 00000010 427 | /// 428 | /// MAV_MODE_FLAG_DECODE_POSITION_TEST 429 | const MavModeFlagDecodePosition mavModeFlagDecodePositionTest = 2; 430 | 431 | /// Eighth bit: 00000001 432 | /// 433 | /// MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE 434 | const MavModeFlagDecodePosition mavModeFlagDecodePositionCustomMode = 1; 435 | 436 | /// 437 | /// MAV_STATE 438 | typedef MavState = int; 439 | 440 | /// Uninitialized system, state is unknown. 441 | /// 442 | /// MAV_STATE_UNINIT 443 | const MavState mavStateUninit = 0; 444 | 445 | /// System is booting up. 446 | /// 447 | /// MAV_STATE_BOOT 448 | const MavState mavStateBoot = 1; 449 | 450 | /// System is calibrating and not flight-ready. 451 | /// 452 | /// MAV_STATE_CALIBRATING 453 | const MavState mavStateCalibrating = 2; 454 | 455 | /// System is grounded and on standby. It can be launched any time. 456 | /// 457 | /// MAV_STATE_STANDBY 458 | const MavState mavStateStandby = 3; 459 | 460 | /// System is active and might be already airborne. Motors are engaged. 461 | /// 462 | /// MAV_STATE_ACTIVE 463 | const MavState mavStateActive = 4; 464 | 465 | /// System is in a non-normal flight mode (failsafe). It can however still navigate. 466 | /// 467 | /// MAV_STATE_CRITICAL 468 | const MavState mavStateCritical = 5; 469 | 470 | /// System is in a non-normal flight mode (failsafe). It lost control over parts or over the whole airframe. It is in mayday and going down. 471 | /// 472 | /// MAV_STATE_EMERGENCY 473 | const MavState mavStateEmergency = 6; 474 | 475 | /// System just initialized its power-down sequence, will shut down now. 476 | /// 477 | /// MAV_STATE_POWEROFF 478 | const MavState mavStatePoweroff = 7; 479 | 480 | /// System is terminating itself (failsafe or commanded). 481 | /// 482 | /// MAV_STATE_FLIGHT_TERMINATION 483 | const MavState mavStateFlightTermination = 8; 484 | 485 | /// Component ids (values) for the different types and instances of onboard hardware/software that might make up a MAVLink system (autopilot, cameras, servos, GPS systems, avoidance systems etc.). 486 | /// Components must use the appropriate ID in their source address when sending messages. Components can also use IDs to determine if they are the intended recipient of an incoming message. The MAV_COMP_ID_ALL value is used to indicate messages that must be processed by all components. 487 | /// When creating new entries, components that can have multiple instances (e.g. cameras, servos etc.) should be allocated sequential values. An appropriate number of values should be left free after these components to allow the number of instances to be expanded. 488 | /// 489 | /// MAV_COMPONENT 490 | typedef MavComponent = int; 491 | 492 | /// Target id (target_component) used to broadcast messages to all components of the receiving system. Components should attempt to process messages with this component ID and forward to components on any other interfaces. Note: This is not a valid *source* component id for a message. 493 | /// 494 | /// MAV_COMP_ID_ALL 495 | const MavComponent mavCompIdAll = 0; 496 | 497 | /// System flight controller component ("autopilot"). Only one autopilot is expected in a particular system. 498 | /// 499 | /// MAV_COMP_ID_AUTOPILOT1 500 | const MavComponent mavCompIdAutopilot1 = 1; 501 | 502 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 503 | /// 504 | /// MAV_COMP_ID_USER1 505 | const MavComponent mavCompIdUser1 = 25; 506 | 507 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 508 | /// 509 | /// MAV_COMP_ID_USER2 510 | const MavComponent mavCompIdUser2 = 26; 511 | 512 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 513 | /// 514 | /// MAV_COMP_ID_USER3 515 | const MavComponent mavCompIdUser3 = 27; 516 | 517 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 518 | /// 519 | /// MAV_COMP_ID_USER4 520 | const MavComponent mavCompIdUser4 = 28; 521 | 522 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 523 | /// 524 | /// MAV_COMP_ID_USER5 525 | const MavComponent mavCompIdUser5 = 29; 526 | 527 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 528 | /// 529 | /// MAV_COMP_ID_USER6 530 | const MavComponent mavCompIdUser6 = 30; 531 | 532 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 533 | /// 534 | /// MAV_COMP_ID_USER7 535 | const MavComponent mavCompIdUser7 = 31; 536 | 537 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 538 | /// 539 | /// MAV_COMP_ID_USER8 540 | const MavComponent mavCompIdUser8 = 32; 541 | 542 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 543 | /// 544 | /// MAV_COMP_ID_USER9 545 | const MavComponent mavCompIdUser9 = 33; 546 | 547 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 548 | /// 549 | /// MAV_COMP_ID_USER10 550 | const MavComponent mavCompIdUser10 = 34; 551 | 552 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 553 | /// 554 | /// MAV_COMP_ID_USER11 555 | const MavComponent mavCompIdUser11 = 35; 556 | 557 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 558 | /// 559 | /// MAV_COMP_ID_USER12 560 | const MavComponent mavCompIdUser12 = 36; 561 | 562 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 563 | /// 564 | /// MAV_COMP_ID_USER13 565 | const MavComponent mavCompIdUser13 = 37; 566 | 567 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 568 | /// 569 | /// MAV_COMP_ID_USER14 570 | const MavComponent mavCompIdUser14 = 38; 571 | 572 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 573 | /// 574 | /// MAV_COMP_ID_USER15 575 | const MavComponent mavCompIdUser15 = 39; 576 | 577 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 578 | /// 579 | /// MAV_COMP_ID_USER16 580 | const MavComponent mavCompIdUser16 = 40; 581 | 582 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 583 | /// 584 | /// MAV_COMP_ID_USER17 585 | const MavComponent mavCompIdUser17 = 41; 586 | 587 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 588 | /// 589 | /// MAV_COMP_ID_USER18 590 | const MavComponent mavCompIdUser18 = 42; 591 | 592 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 593 | /// 594 | /// MAV_COMP_ID_USER19 595 | const MavComponent mavCompIdUser19 = 43; 596 | 597 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 598 | /// 599 | /// MAV_COMP_ID_USER20 600 | const MavComponent mavCompIdUser20 = 44; 601 | 602 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 603 | /// 604 | /// MAV_COMP_ID_USER21 605 | const MavComponent mavCompIdUser21 = 45; 606 | 607 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 608 | /// 609 | /// MAV_COMP_ID_USER22 610 | const MavComponent mavCompIdUser22 = 46; 611 | 612 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 613 | /// 614 | /// MAV_COMP_ID_USER23 615 | const MavComponent mavCompIdUser23 = 47; 616 | 617 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 618 | /// 619 | /// MAV_COMP_ID_USER24 620 | const MavComponent mavCompIdUser24 = 48; 621 | 622 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 623 | /// 624 | /// MAV_COMP_ID_USER25 625 | const MavComponent mavCompIdUser25 = 49; 626 | 627 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 628 | /// 629 | /// MAV_COMP_ID_USER26 630 | const MavComponent mavCompIdUser26 = 50; 631 | 632 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 633 | /// 634 | /// MAV_COMP_ID_USER27 635 | const MavComponent mavCompIdUser27 = 51; 636 | 637 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 638 | /// 639 | /// MAV_COMP_ID_USER28 640 | const MavComponent mavCompIdUser28 = 52; 641 | 642 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 643 | /// 644 | /// MAV_COMP_ID_USER29 645 | const MavComponent mavCompIdUser29 = 53; 646 | 647 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 648 | /// 649 | /// MAV_COMP_ID_USER30 650 | const MavComponent mavCompIdUser30 = 54; 651 | 652 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 653 | /// 654 | /// MAV_COMP_ID_USER31 655 | const MavComponent mavCompIdUser31 = 55; 656 | 657 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 658 | /// 659 | /// MAV_COMP_ID_USER32 660 | const MavComponent mavCompIdUser32 = 56; 661 | 662 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 663 | /// 664 | /// MAV_COMP_ID_USER33 665 | const MavComponent mavCompIdUser33 = 57; 666 | 667 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 668 | /// 669 | /// MAV_COMP_ID_USER34 670 | const MavComponent mavCompIdUser34 = 58; 671 | 672 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 673 | /// 674 | /// MAV_COMP_ID_USER35 675 | const MavComponent mavCompIdUser35 = 59; 676 | 677 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 678 | /// 679 | /// MAV_COMP_ID_USER36 680 | const MavComponent mavCompIdUser36 = 60; 681 | 682 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 683 | /// 684 | /// MAV_COMP_ID_USER37 685 | const MavComponent mavCompIdUser37 = 61; 686 | 687 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 688 | /// 689 | /// MAV_COMP_ID_USER38 690 | const MavComponent mavCompIdUser38 = 62; 691 | 692 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 693 | /// 694 | /// MAV_COMP_ID_USER39 695 | const MavComponent mavCompIdUser39 = 63; 696 | 697 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 698 | /// 699 | /// MAV_COMP_ID_USER40 700 | const MavComponent mavCompIdUser40 = 64; 701 | 702 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 703 | /// 704 | /// MAV_COMP_ID_USER41 705 | const MavComponent mavCompIdUser41 = 65; 706 | 707 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 708 | /// 709 | /// MAV_COMP_ID_USER42 710 | const MavComponent mavCompIdUser42 = 66; 711 | 712 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 713 | /// 714 | /// MAV_COMP_ID_USER43 715 | const MavComponent mavCompIdUser43 = 67; 716 | 717 | /// Telemetry radio (e.g. SiK radio, or other component that emits RADIO_STATUS messages). 718 | /// 719 | /// MAV_COMP_ID_TELEMETRY_RADIO 720 | const MavComponent mavCompIdTelemetryRadio = 68; 721 | 722 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 723 | /// 724 | /// MAV_COMP_ID_USER45 725 | const MavComponent mavCompIdUser45 = 69; 726 | 727 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 728 | /// 729 | /// MAV_COMP_ID_USER46 730 | const MavComponent mavCompIdUser46 = 70; 731 | 732 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 733 | /// 734 | /// MAV_COMP_ID_USER47 735 | const MavComponent mavCompIdUser47 = 71; 736 | 737 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 738 | /// 739 | /// MAV_COMP_ID_USER48 740 | const MavComponent mavCompIdUser48 = 72; 741 | 742 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 743 | /// 744 | /// MAV_COMP_ID_USER49 745 | const MavComponent mavCompIdUser49 = 73; 746 | 747 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 748 | /// 749 | /// MAV_COMP_ID_USER50 750 | const MavComponent mavCompIdUser50 = 74; 751 | 752 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 753 | /// 754 | /// MAV_COMP_ID_USER51 755 | const MavComponent mavCompIdUser51 = 75; 756 | 757 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 758 | /// 759 | /// MAV_COMP_ID_USER52 760 | const MavComponent mavCompIdUser52 = 76; 761 | 762 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 763 | /// 764 | /// MAV_COMP_ID_USER53 765 | const MavComponent mavCompIdUser53 = 77; 766 | 767 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 768 | /// 769 | /// MAV_COMP_ID_USER54 770 | const MavComponent mavCompIdUser54 = 78; 771 | 772 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 773 | /// 774 | /// MAV_COMP_ID_USER55 775 | const MavComponent mavCompIdUser55 = 79; 776 | 777 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 778 | /// 779 | /// MAV_COMP_ID_USER56 780 | const MavComponent mavCompIdUser56 = 80; 781 | 782 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 783 | /// 784 | /// MAV_COMP_ID_USER57 785 | const MavComponent mavCompIdUser57 = 81; 786 | 787 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 788 | /// 789 | /// MAV_COMP_ID_USER58 790 | const MavComponent mavCompIdUser58 = 82; 791 | 792 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 793 | /// 794 | /// MAV_COMP_ID_USER59 795 | const MavComponent mavCompIdUser59 = 83; 796 | 797 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 798 | /// 799 | /// MAV_COMP_ID_USER60 800 | const MavComponent mavCompIdUser60 = 84; 801 | 802 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 803 | /// 804 | /// MAV_COMP_ID_USER61 805 | const MavComponent mavCompIdUser61 = 85; 806 | 807 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 808 | /// 809 | /// MAV_COMP_ID_USER62 810 | const MavComponent mavCompIdUser62 = 86; 811 | 812 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 813 | /// 814 | /// MAV_COMP_ID_USER63 815 | const MavComponent mavCompIdUser63 = 87; 816 | 817 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 818 | /// 819 | /// MAV_COMP_ID_USER64 820 | const MavComponent mavCompIdUser64 = 88; 821 | 822 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 823 | /// 824 | /// MAV_COMP_ID_USER65 825 | const MavComponent mavCompIdUser65 = 89; 826 | 827 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 828 | /// 829 | /// MAV_COMP_ID_USER66 830 | const MavComponent mavCompIdUser66 = 90; 831 | 832 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 833 | /// 834 | /// MAV_COMP_ID_USER67 835 | const MavComponent mavCompIdUser67 = 91; 836 | 837 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 838 | /// 839 | /// MAV_COMP_ID_USER68 840 | const MavComponent mavCompIdUser68 = 92; 841 | 842 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 843 | /// 844 | /// MAV_COMP_ID_USER69 845 | const MavComponent mavCompIdUser69 = 93; 846 | 847 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 848 | /// 849 | /// MAV_COMP_ID_USER70 850 | const MavComponent mavCompIdUser70 = 94; 851 | 852 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 853 | /// 854 | /// MAV_COMP_ID_USER71 855 | const MavComponent mavCompIdUser71 = 95; 856 | 857 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 858 | /// 859 | /// MAV_COMP_ID_USER72 860 | const MavComponent mavCompIdUser72 = 96; 861 | 862 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 863 | /// 864 | /// MAV_COMP_ID_USER73 865 | const MavComponent mavCompIdUser73 = 97; 866 | 867 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 868 | /// 869 | /// MAV_COMP_ID_USER74 870 | const MavComponent mavCompIdUser74 = 98; 871 | 872 | /// Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network. 873 | /// 874 | /// MAV_COMP_ID_USER75 875 | const MavComponent mavCompIdUser75 = 99; 876 | 877 | /// Camera #1. 878 | /// 879 | /// MAV_COMP_ID_CAMERA 880 | const MavComponent mavCompIdCamera = 100; 881 | 882 | /// Camera #2. 883 | /// 884 | /// MAV_COMP_ID_CAMERA2 885 | const MavComponent mavCompIdCamera2 = 101; 886 | 887 | /// Camera #3. 888 | /// 889 | /// MAV_COMP_ID_CAMERA3 890 | const MavComponent mavCompIdCamera3 = 102; 891 | 892 | /// Camera #4. 893 | /// 894 | /// MAV_COMP_ID_CAMERA4 895 | const MavComponent mavCompIdCamera4 = 103; 896 | 897 | /// Camera #5. 898 | /// 899 | /// MAV_COMP_ID_CAMERA5 900 | const MavComponent mavCompIdCamera5 = 104; 901 | 902 | /// Camera #6. 903 | /// 904 | /// MAV_COMP_ID_CAMERA6 905 | const MavComponent mavCompIdCamera6 = 105; 906 | 907 | /// Servo #1. 908 | /// 909 | /// MAV_COMP_ID_SERVO1 910 | const MavComponent mavCompIdServo1 = 140; 911 | 912 | /// Servo #2. 913 | /// 914 | /// MAV_COMP_ID_SERVO2 915 | const MavComponent mavCompIdServo2 = 141; 916 | 917 | /// Servo #3. 918 | /// 919 | /// MAV_COMP_ID_SERVO3 920 | const MavComponent mavCompIdServo3 = 142; 921 | 922 | /// Servo #4. 923 | /// 924 | /// MAV_COMP_ID_SERVO4 925 | const MavComponent mavCompIdServo4 = 143; 926 | 927 | /// Servo #5. 928 | /// 929 | /// MAV_COMP_ID_SERVO5 930 | const MavComponent mavCompIdServo5 = 144; 931 | 932 | /// Servo #6. 933 | /// 934 | /// MAV_COMP_ID_SERVO6 935 | const MavComponent mavCompIdServo6 = 145; 936 | 937 | /// Servo #7. 938 | /// 939 | /// MAV_COMP_ID_SERVO7 940 | const MavComponent mavCompIdServo7 = 146; 941 | 942 | /// Servo #8. 943 | /// 944 | /// MAV_COMP_ID_SERVO8 945 | const MavComponent mavCompIdServo8 = 147; 946 | 947 | /// Servo #9. 948 | /// 949 | /// MAV_COMP_ID_SERVO9 950 | const MavComponent mavCompIdServo9 = 148; 951 | 952 | /// Servo #10. 953 | /// 954 | /// MAV_COMP_ID_SERVO10 955 | const MavComponent mavCompIdServo10 = 149; 956 | 957 | /// Servo #11. 958 | /// 959 | /// MAV_COMP_ID_SERVO11 960 | const MavComponent mavCompIdServo11 = 150; 961 | 962 | /// Servo #12. 963 | /// 964 | /// MAV_COMP_ID_SERVO12 965 | const MavComponent mavCompIdServo12 = 151; 966 | 967 | /// Servo #13. 968 | /// 969 | /// MAV_COMP_ID_SERVO13 970 | const MavComponent mavCompIdServo13 = 152; 971 | 972 | /// Servo #14. 973 | /// 974 | /// MAV_COMP_ID_SERVO14 975 | const MavComponent mavCompIdServo14 = 153; 976 | 977 | /// Gimbal #1. 978 | /// 979 | /// MAV_COMP_ID_GIMBAL 980 | const MavComponent mavCompIdGimbal = 154; 981 | 982 | /// Logging component. 983 | /// 984 | /// MAV_COMP_ID_LOG 985 | const MavComponent mavCompIdLog = 155; 986 | 987 | /// Automatic Dependent Surveillance-Broadcast (ADS-B) component. 988 | /// 989 | /// MAV_COMP_ID_ADSB 990 | const MavComponent mavCompIdAdsb = 156; 991 | 992 | /// On Screen Display (OSD) devices for video links. 993 | /// 994 | /// MAV_COMP_ID_OSD 995 | const MavComponent mavCompIdOsd = 157; 996 | 997 | /// Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter microservice. 998 | /// 999 | /// MAV_COMP_ID_PERIPHERAL 1000 | const MavComponent mavCompIdPeripheral = 158; 1001 | 1002 | /// Gimbal ID for QX1. 1003 | /// 1004 | /// MAV_COMP_ID_QX1_GIMBAL 1005 | @Deprecated( 1006 | "Replaced by [MAV_COMP_ID_GIMBAL] since 2018-11. All gimbals should use MAV_COMP_ID_GIMBAL.") 1007 | const MavComponent mavCompIdQx1Gimbal = 159; 1008 | 1009 | /// FLARM collision alert component. 1010 | /// 1011 | /// MAV_COMP_ID_FLARM 1012 | const MavComponent mavCompIdFlarm = 160; 1013 | 1014 | /// Parachute component. 1015 | /// 1016 | /// MAV_COMP_ID_PARACHUTE 1017 | const MavComponent mavCompIdParachute = 161; 1018 | 1019 | /// Winch component. 1020 | /// 1021 | /// MAV_COMP_ID_WINCH 1022 | const MavComponent mavCompIdWinch = 169; 1023 | 1024 | /// Gimbal #2. 1025 | /// 1026 | /// MAV_COMP_ID_GIMBAL2 1027 | const MavComponent mavCompIdGimbal2 = 171; 1028 | 1029 | /// Gimbal #3. 1030 | /// 1031 | /// MAV_COMP_ID_GIMBAL3 1032 | const MavComponent mavCompIdGimbal3 = 172; 1033 | 1034 | /// Gimbal #4 1035 | /// 1036 | /// MAV_COMP_ID_GIMBAL4 1037 | const MavComponent mavCompIdGimbal4 = 173; 1038 | 1039 | /// Gimbal #5. 1040 | /// 1041 | /// MAV_COMP_ID_GIMBAL5 1042 | const MavComponent mavCompIdGimbal5 = 174; 1043 | 1044 | /// Gimbal #6. 1045 | /// 1046 | /// MAV_COMP_ID_GIMBAL6 1047 | const MavComponent mavCompIdGimbal6 = 175; 1048 | 1049 | /// Battery #1. 1050 | /// 1051 | /// MAV_COMP_ID_BATTERY 1052 | const MavComponent mavCompIdBattery = 180; 1053 | 1054 | /// Battery #2. 1055 | /// 1056 | /// MAV_COMP_ID_BATTERY2 1057 | const MavComponent mavCompIdBattery2 = 181; 1058 | 1059 | /// CAN over MAVLink client. 1060 | /// 1061 | /// MAV_COMP_ID_MAVCAN 1062 | const MavComponent mavCompIdMavcan = 189; 1063 | 1064 | /// Component that can generate/supply a mission flight plan (e.g. GCS or developer API). 1065 | /// 1066 | /// MAV_COMP_ID_MISSIONPLANNER 1067 | const MavComponent mavCompIdMissionplanner = 190; 1068 | 1069 | /// Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. 1070 | /// 1071 | /// MAV_COMP_ID_ONBOARD_COMPUTER 1072 | const MavComponent mavCompIdOnboardComputer = 191; 1073 | 1074 | /// Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. 1075 | /// 1076 | /// MAV_COMP_ID_ONBOARD_COMPUTER2 1077 | const MavComponent mavCompIdOnboardComputer2 = 192; 1078 | 1079 | /// Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. 1080 | /// 1081 | /// MAV_COMP_ID_ONBOARD_COMPUTER3 1082 | const MavComponent mavCompIdOnboardComputer3 = 193; 1083 | 1084 | /// Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on. 1085 | /// 1086 | /// MAV_COMP_ID_ONBOARD_COMPUTER4 1087 | const MavComponent mavCompIdOnboardComputer4 = 194; 1088 | 1089 | /// Component that finds an optimal path between points based on a certain constraint (e.g. minimum snap, shortest path, cost, etc.). 1090 | /// 1091 | /// MAV_COMP_ID_PATHPLANNER 1092 | const MavComponent mavCompIdPathplanner = 195; 1093 | 1094 | /// Component that plans a collision free path between two points. 1095 | /// 1096 | /// MAV_COMP_ID_OBSTACLE_AVOIDANCE 1097 | const MavComponent mavCompIdObstacleAvoidance = 196; 1098 | 1099 | /// Component that provides position estimates using VIO techniques. 1100 | /// 1101 | /// MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY 1102 | const MavComponent mavCompIdVisualInertialOdometry = 197; 1103 | 1104 | /// Component that manages pairing of vehicle and GCS. 1105 | /// 1106 | /// MAV_COMP_ID_PAIRING_MANAGER 1107 | const MavComponent mavCompIdPairingManager = 198; 1108 | 1109 | /// Inertial Measurement Unit (IMU) #1. 1110 | /// 1111 | /// MAV_COMP_ID_IMU 1112 | const MavComponent mavCompIdImu = 200; 1113 | 1114 | /// Inertial Measurement Unit (IMU) #2. 1115 | /// 1116 | /// MAV_COMP_ID_IMU_2 1117 | const MavComponent mavCompIdImu2 = 201; 1118 | 1119 | /// Inertial Measurement Unit (IMU) #3. 1120 | /// 1121 | /// MAV_COMP_ID_IMU_3 1122 | const MavComponent mavCompIdImu3 = 202; 1123 | 1124 | /// GPS #1. 1125 | /// 1126 | /// MAV_COMP_ID_GPS 1127 | const MavComponent mavCompIdGps = 220; 1128 | 1129 | /// GPS #2. 1130 | /// 1131 | /// MAV_COMP_ID_GPS2 1132 | const MavComponent mavCompIdGps2 = 221; 1133 | 1134 | /// Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet). 1135 | /// 1136 | /// MAV_COMP_ID_ODID_TXRX_1 1137 | const MavComponent mavCompIdOdidTxrx1 = 236; 1138 | 1139 | /// Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet). 1140 | /// 1141 | /// MAV_COMP_ID_ODID_TXRX_2 1142 | const MavComponent mavCompIdOdidTxrx2 = 237; 1143 | 1144 | /// Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet). 1145 | /// 1146 | /// MAV_COMP_ID_ODID_TXRX_3 1147 | const MavComponent mavCompIdOdidTxrx3 = 238; 1148 | 1149 | /// Component to bridge MAVLink to UDP (i.e. from a UART). 1150 | /// 1151 | /// MAV_COMP_ID_UDP_BRIDGE 1152 | const MavComponent mavCompIdUdpBridge = 240; 1153 | 1154 | /// Component to bridge to UART (i.e. from UDP). 1155 | /// 1156 | /// MAV_COMP_ID_UART_BRIDGE 1157 | const MavComponent mavCompIdUartBridge = 241; 1158 | 1159 | /// Component handling TUNNEL messages (e.g. vendor specific GUI of a component). 1160 | /// 1161 | /// MAV_COMP_ID_TUNNEL_NODE 1162 | const MavComponent mavCompIdTunnelNode = 242; 1163 | 1164 | /// Illuminator 1165 | /// 1166 | /// MAV_COMP_ID_ILLUMINATOR 1167 | const MavComponent mavCompIdIlluminator = 243; 1168 | 1169 | /// Deprecated, don't use. Component for handling system messages (e.g. to ARM, takeoff, etc.). 1170 | /// 1171 | /// MAV_COMP_ID_SYSTEM_CONTROL 1172 | @Deprecated( 1173 | "Replaced by [MAV_COMP_ID_ALL] since 2018-11. System control does not require a separate component ID. Instead, system commands should be sent with target_component=MAV_COMP_ID_ALL allowing the target component to use any appropriate component id.") 1174 | const MavComponent mavCompIdSystemControl = 250; 1175 | 1176 | /// The heartbeat message shows that a system or component is present and responding. The type and autopilot fields (along with the message component id), allow the receiving system to treat further messages from this system appropriately (e.g. by laying out the user interface based on the autopilot). This microservice is documented at https://mavlink.io/en/services/heartbeat.html 1177 | /// 1178 | /// HEARTBEAT 1179 | class Heartbeat implements MavlinkMessage { 1180 | static const int _mavlinkMessageId = 0; 1181 | 1182 | static const int _mavlinkCrcExtra = 50; 1183 | 1184 | static const int mavlinkEncodedLength = 9; 1185 | 1186 | @override 1187 | int get mavlinkMessageId => _mavlinkMessageId; 1188 | 1189 | @override 1190 | int get mavlinkCrcExtra => _mavlinkCrcExtra; 1191 | 1192 | /// A bitfield for use for autopilot-specific flags 1193 | /// 1194 | /// MAVLink type: uint32_t 1195 | /// 1196 | /// custom_mode 1197 | final uint32_t customMode; 1198 | 1199 | /// Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type. 1200 | /// 1201 | /// MAVLink type: uint8_t 1202 | /// 1203 | /// enum: [MavType] 1204 | /// 1205 | /// type 1206 | final MavType type; 1207 | 1208 | /// Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers. 1209 | /// 1210 | /// MAVLink type: uint8_t 1211 | /// 1212 | /// enum: [MavAutopilot] 1213 | /// 1214 | /// autopilot 1215 | final MavAutopilot autopilot; 1216 | 1217 | /// System mode bitmap. 1218 | /// 1219 | /// MAVLink type: uint8_t 1220 | /// 1221 | /// enum: [MavModeFlag] 1222 | /// 1223 | /// base_mode 1224 | final MavModeFlag baseMode; 1225 | 1226 | /// System status flag. 1227 | /// 1228 | /// MAVLink type: uint8_t 1229 | /// 1230 | /// enum: [MavState] 1231 | /// 1232 | /// system_status 1233 | final MavState systemStatus; 1234 | 1235 | /// MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version 1236 | /// 1237 | /// MAVLink type: uint8_t 1238 | /// 1239 | /// mavlink_version 1240 | final uint8_t mavlinkVersion; 1241 | 1242 | Heartbeat({ 1243 | required this.customMode, 1244 | required this.type, 1245 | required this.autopilot, 1246 | required this.baseMode, 1247 | required this.systemStatus, 1248 | required this.mavlinkVersion, 1249 | }); 1250 | 1251 | Heartbeat copyWith({ 1252 | uint32_t? customMode, 1253 | MavType? type, 1254 | MavAutopilot? autopilot, 1255 | MavModeFlag? baseMode, 1256 | MavState? systemStatus, 1257 | uint8_t? mavlinkVersion, 1258 | }) { 1259 | return Heartbeat( 1260 | customMode: customMode ?? this.customMode, 1261 | type: type ?? this.type, 1262 | autopilot: autopilot ?? this.autopilot, 1263 | baseMode: baseMode ?? this.baseMode, 1264 | systemStatus: systemStatus ?? this.systemStatus, 1265 | mavlinkVersion: mavlinkVersion ?? this.mavlinkVersion, 1266 | ); 1267 | } 1268 | 1269 | factory Heartbeat.parse(ByteData data_) { 1270 | if (data_.lengthInBytes < Heartbeat.mavlinkEncodedLength) { 1271 | var len = Heartbeat.mavlinkEncodedLength - data_.lengthInBytes; 1272 | var d = data_.buffer.asUint8List().sublist(0, data_.lengthInBytes) + 1273 | List.filled(len, 0); 1274 | data_ = Uint8List.fromList(d).buffer.asByteData(); 1275 | } 1276 | var customMode = data_.getUint32(0, Endian.little); 1277 | var type = data_.getUint8(4); 1278 | var autopilot = data_.getUint8(5); 1279 | var baseMode = data_.getUint8(6); 1280 | var systemStatus = data_.getUint8(7); 1281 | var mavlinkVersion = data_.getUint8(8); 1282 | 1283 | return Heartbeat( 1284 | customMode: customMode, 1285 | type: type, 1286 | autopilot: autopilot, 1287 | baseMode: baseMode, 1288 | systemStatus: systemStatus, 1289 | mavlinkVersion: mavlinkVersion); 1290 | } 1291 | 1292 | @override 1293 | ByteData serialize() { 1294 | var data_ = ByteData(mavlinkEncodedLength); 1295 | data_.setUint32(0, customMode, Endian.little); 1296 | data_.setUint8(4, type); 1297 | data_.setUint8(5, autopilot); 1298 | data_.setUint8(6, baseMode); 1299 | data_.setUint8(7, systemStatus); 1300 | data_.setUint8(8, mavlinkVersion); 1301 | return data_; 1302 | } 1303 | } 1304 | 1305 | /// Version and capability of protocol version. This message can be requested with MAV_CMD_REQUEST_MESSAGE and is used as part of the handshaking to establish which MAVLink version should be used on the network. Every node should respond to a request for PROTOCOL_VERSION to enable the handshaking. Library implementers should consider adding this into the default decoding state machine to allow the protocol core to respond directly. 1306 | /// 1307 | /// PROTOCOL_VERSION 1308 | class ProtocolVersion implements MavlinkMessage { 1309 | static const int _mavlinkMessageId = 300; 1310 | 1311 | static const int _mavlinkCrcExtra = 217; 1312 | 1313 | static const int mavlinkEncodedLength = 22; 1314 | 1315 | @override 1316 | int get mavlinkMessageId => _mavlinkMessageId; 1317 | 1318 | @override 1319 | int get mavlinkCrcExtra => _mavlinkCrcExtra; 1320 | 1321 | /// Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc. 1322 | /// 1323 | /// MAVLink type: uint16_t 1324 | /// 1325 | /// version 1326 | final uint16_t version; 1327 | 1328 | /// Minimum MAVLink version supported 1329 | /// 1330 | /// MAVLink type: uint16_t 1331 | /// 1332 | /// min_version 1333 | final uint16_t minVersion; 1334 | 1335 | /// Maximum MAVLink version supported (set to the same value as version by default) 1336 | /// 1337 | /// MAVLink type: uint16_t 1338 | /// 1339 | /// max_version 1340 | final uint16_t maxVersion; 1341 | 1342 | /// The first 8 bytes (not characters printed in hex!) of the git hash. 1343 | /// 1344 | /// MAVLink type: uint8_t[8] 1345 | /// 1346 | /// spec_version_hash 1347 | final List specVersionHash; 1348 | 1349 | /// The first 8 bytes (not characters printed in hex!) of the git hash. 1350 | /// 1351 | /// MAVLink type: uint8_t[8] 1352 | /// 1353 | /// library_version_hash 1354 | final List libraryVersionHash; 1355 | 1356 | ProtocolVersion({ 1357 | required this.version, 1358 | required this.minVersion, 1359 | required this.maxVersion, 1360 | required this.specVersionHash, 1361 | required this.libraryVersionHash, 1362 | }); 1363 | 1364 | ProtocolVersion copyWith({ 1365 | uint16_t? version, 1366 | uint16_t? minVersion, 1367 | uint16_t? maxVersion, 1368 | List? specVersionHash, 1369 | List? libraryVersionHash, 1370 | }) { 1371 | return ProtocolVersion( 1372 | version: version ?? this.version, 1373 | minVersion: minVersion ?? this.minVersion, 1374 | maxVersion: maxVersion ?? this.maxVersion, 1375 | specVersionHash: specVersionHash ?? this.specVersionHash, 1376 | libraryVersionHash: libraryVersionHash ?? this.libraryVersionHash, 1377 | ); 1378 | } 1379 | 1380 | factory ProtocolVersion.parse(ByteData data_) { 1381 | if (data_.lengthInBytes < ProtocolVersion.mavlinkEncodedLength) { 1382 | var len = ProtocolVersion.mavlinkEncodedLength - data_.lengthInBytes; 1383 | var d = data_.buffer.asUint8List().sublist(0, data_.lengthInBytes) + 1384 | List.filled(len, 0); 1385 | data_ = Uint8List.fromList(d).buffer.asByteData(); 1386 | } 1387 | var version = data_.getUint16(0, Endian.little); 1388 | var minVersion = data_.getUint16(2, Endian.little); 1389 | var maxVersion = data_.getUint16(4, Endian.little); 1390 | var specVersionHash = MavlinkMessage.asUint8List(data_, 6, 8); 1391 | var libraryVersionHash = MavlinkMessage.asUint8List(data_, 14, 8); 1392 | 1393 | return ProtocolVersion( 1394 | version: version, 1395 | minVersion: minVersion, 1396 | maxVersion: maxVersion, 1397 | specVersionHash: specVersionHash, 1398 | libraryVersionHash: libraryVersionHash); 1399 | } 1400 | 1401 | @override 1402 | ByteData serialize() { 1403 | var data_ = ByteData(mavlinkEncodedLength); 1404 | data_.setUint16(0, version, Endian.little); 1405 | data_.setUint16(2, minVersion, Endian.little); 1406 | data_.setUint16(4, maxVersion, Endian.little); 1407 | MavlinkMessage.setUint8List(data_, 6, specVersionHash); 1408 | MavlinkMessage.setUint8List(data_, 14, libraryVersionHash); 1409 | return data_; 1410 | } 1411 | } 1412 | 1413 | class MavlinkDialectStandard implements MavlinkDialect { 1414 | static const int mavlinkVersion = 3; 1415 | 1416 | @override 1417 | int get version => mavlinkVersion; 1418 | 1419 | @override 1420 | MavlinkMessage? parse(int messageID, ByteData data) { 1421 | switch (messageID) { 1422 | case 0: 1423 | return Heartbeat.parse(data); 1424 | case 300: 1425 | return ProtocolVersion.parse(data); 1426 | default: 1427 | return null; 1428 | } 1429 | } 1430 | 1431 | @override 1432 | int crcExtra(int messageID) { 1433 | switch (messageID) { 1434 | case 0: 1435 | return Heartbeat._mavlinkCrcExtra; 1436 | case 300: 1437 | return ProtocolVersion._mavlinkCrcExtra; 1438 | default: 1439 | return -1; 1440 | } 1441 | } 1442 | } 1443 | --------------------------------------------------------------------------------