Rebase from 'upstream'
This commit is contained in:
24
.github/workflows/test_and_deploy.yml
vendored
24
.github/workflows/test_and_deploy.yml
vendored
@@ -52,6 +52,30 @@ jobs:
|
||||
run: |
|
||||
./scripts/test.sh py
|
||||
|
||||
build-cmake-c-example:
|
||||
name: Build cmake C example
|
||||
runs-on: ubuntu-22.04
|
||||
steps:
|
||||
- uses: actions/checkout@v2
|
||||
with:
|
||||
submodules: 'recursive'
|
||||
- name: Install dependencies
|
||||
run: |
|
||||
sudo apt update
|
||||
sudo apt install -y python3 python3-pip
|
||||
- name: Install pip dependencies
|
||||
run: |
|
||||
python3 -m pip install -r pymavlink/requirements.txt
|
||||
- name: Install MAVLink headers
|
||||
run: |
|
||||
cmake -Bbuild -H. -DCMAKE_INSTALL_PREFIX=install
|
||||
cmake --build build --target install
|
||||
- name: Build example
|
||||
run: |
|
||||
cd examples/c
|
||||
cmake -Bbuild -H. -DCMAKE_PREFIX_PATH=$(pwd)/../../install
|
||||
cmake --build build
|
||||
|
||||
node-tests:
|
||||
name: Node ${{ matrix.node-version }} test
|
||||
runs-on: ubuntu-20.04
|
||||
|
||||
3
MAVLinkConfig.cmake.in
Normal file
3
MAVLinkConfig.cmake.in
Normal file
@@ -0,0 +1,3 @@
|
||||
get_filename_component(MAVLINK_CMAKE_DIR "${CMAKE_CURRENT_LIST_FILE}" PATH)
|
||||
include("${MAVLINK_CMAKE_DIR}/MAVLinkTargets.cmake")
|
||||
|
||||
69
README.md
69
README.md
@@ -1,6 +1,6 @@
|
||||
[](https://github.com/mavlink/mavlink/actions?query=branch%3Amaster)
|
||||
|
||||
## MAVLink ##
|
||||
# MAVLink
|
||||
|
||||
MAVLink -- Micro Air Vehicle Message Marshalling Library.
|
||||
|
||||
@@ -8,8 +8,71 @@ MAVLink is a very lightweight, header-only message library for communication bet
|
||||
|
||||
> **Tip** MAVLink is very well suited for applications with very limited communication bandwidth. Its reference implementation in C is highly optimized for resource-constrained systems with limited RAM and flash memory. It is field-proven and deployed in many products where it serves as interoperability interface between components of different manufacturers.
|
||||
|
||||
Key Links:
|
||||
|
||||
## Quick start
|
||||
|
||||
### Generate C headers
|
||||
|
||||
To install the minimal MAVLink environment on Ubuntu LTS 20.04 or 22.04, enter the following on a terminal:
|
||||
|
||||
```bash
|
||||
# Dependencies
|
||||
sudo apt install python3-pip
|
||||
|
||||
# Clone mavlink into the directory of your choice
|
||||
git clone https://github.com/mavlink/mavlink.git --recursive
|
||||
cd mavlink
|
||||
|
||||
python3 -m pip install pymavlink/requirements.txt
|
||||
```
|
||||
|
||||
You can then build the MAVLink2 C-library for `message_definitions/v1.0/common.xml` from the `/mavlink` directory as shown:
|
||||
|
||||
```bash
|
||||
python3 -m pymavlink.tools.mavgen --lang=C --wire-protocol=2.0 --output=generated/include/mavlink/v2.0 message_definitions/v1.0/common.xml
|
||||
```
|
||||
|
||||
### Use from cmake
|
||||
|
||||
To include the headers in cmake, install them locally, e.g. into the directory `install`:
|
||||
|
||||
```
|
||||
cmake -Bbuild -H. -DCMAKE_INSTALL_PREFIX=install -DMAVLINK_DIALECT=common -DMAVLINK_VERSION=2.0
|
||||
cmake --build build --target install
|
||||
```
|
||||
|
||||
Then use `find_package` to get the dependency in `CMakeLists.txt`:
|
||||
|
||||
```
|
||||
find_package(MAVLink REQUIRED)
|
||||
|
||||
add_executable(my_program my_program.c)
|
||||
|
||||
target_link_libraries(my_program PRIVATE MAVLink::mavlink)
|
||||
```
|
||||
|
||||
And pass the local install directory to cmake (adapt to your directory structure):
|
||||
|
||||
```
|
||||
cd ../my_program
|
||||
cmake -Bbuild -H. -DCMAKE_PREFIX_PATH=../mavlink/install
|
||||
```
|
||||
|
||||
For a full example, check [examples/c](examples/c).
|
||||
|
||||
*Note: even though we use `target_link_libraries` in cmake, it doesn't actually "link" to MAVLink as it's just a header-only library.*
|
||||
|
||||
### Other instructions
|
||||
|
||||
Instructions for using the C libraries are then covered in [Using C MAVLink Libraries (mavgen)](https://mavlink.io/en/mavgen_c/).
|
||||
|
||||
> **Note:** [Installing the MAVLink Toolchain](https://mavlink.io/en/getting_started/installation.html) explains how to install MAVLink on other Ubuntu platforms and Windows, while [Generating MAVLink Libraries](https://mavlink.io/en/getting_started/generate_libraries.html) explains how to build MAVLink for the other programming languages [supported by the project](https://mavlink.io/en/#supported_languages).
|
||||
> The sub-topics of [Using MAVLink Libraries](https://mavlink.io/en/getting_started/use_libraries.html) explain how to use the generated libraries.
|
||||
|
||||
|
||||
## Key Links
|
||||
|
||||
* [Documentation/Website](https://mavlink.io/en/) (mavlink.io/en/)
|
||||
* [Discussion/Support](https://mavlink.io/en/#support) (Slack)
|
||||
* [Discussion/Support](https://mavlink.io/en/#support)
|
||||
* [Contributing](https://mavlink.io/en/contributing/contributing.html)
|
||||
* [License](https://mavlink.io/en/#license)
|
||||
|
||||
@@ -1 +0,0 @@
|
||||
Welcome to installation. This program will guide you through the installation of this software.
|
||||
@@ -1,32 +0,0 @@
|
||||
# Always include srcdir and builddir in include path
|
||||
# This saves typing ${CMAKE_CURRENT_SOURCE_DIR} ${CMAKE_CURRENT_BINARY} in
|
||||
# about every subdir
|
||||
# since cmake 2.4.0
|
||||
set(CMAKE_INCLUDE_CURRENT_DIR ON)
|
||||
|
||||
# Put the include dirs which are in the source or build tree
|
||||
# before all other include dirs, so the headers in the sources
|
||||
# are prefered over the already installed ones
|
||||
# since cmake 2.4.1
|
||||
set(CMAKE_INCLUDE_DIRECTORIES_PROJECT_BEFORE ON)
|
||||
|
||||
# Use colored output
|
||||
# since cmake 2.4.0
|
||||
set(CMAKE_COLOR_MAKEFILE ON)
|
||||
|
||||
# Define the generic version of the libraries here
|
||||
set(GENERIC_LIB_VERSION "0.1.0")
|
||||
set(GENERIC_LIB_SOVERSION "0")
|
||||
|
||||
# Set the default build type to release with debug info
|
||||
if (NOT CMAKE_BUILD_TYPE)
|
||||
set(CMAKE_BUILD_TYPE RelWithDebInfo
|
||||
CACHE STRING
|
||||
"Choose the type of build, options are: None Debug Release RelWithDebInfo MinSizeRel."
|
||||
)
|
||||
endif (NOT CMAKE_BUILD_TYPE)
|
||||
|
||||
# disallow in-source build
|
||||
include(MacroEnsureOutOfSourceBuild)
|
||||
macro_ensure_out_of_source_build("${PROJECT_NAME} requires an out of source build.
|
||||
Please create a separate build directory and run 'cmake /path/to/${PROJECT_NAME} [options]' there.")
|
||||
@@ -1,90 +0,0 @@
|
||||
# define system dependent compiler flags
|
||||
|
||||
include(CheckCCompilerFlag)
|
||||
include(MacroCheckCCompilerFlagSSP)
|
||||
|
||||
#
|
||||
# Define GNUCC compiler flags
|
||||
#
|
||||
if (${CMAKE_C_COMPILER_ID} MATCHES GNU)
|
||||
|
||||
# add -Wconversion ?
|
||||
#set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -std=gnu99 -pedantic -pedantic-errors")
|
||||
#set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -Wextra -Wshadow -Wmissing-prototypes -Wdeclaration-after-statement")
|
||||
#set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wunused -Wfloat-equal -Wpointer-arith -Wwrite-strings -Wformat-security")
|
||||
#set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wmissing-format-attribute")
|
||||
|
||||
#set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -pedantic -pedantic-errors")
|
||||
#set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra -Wshadow")
|
||||
#set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wunused -Wfloat-equal -Wpointer-arith -Wwrite-strings -Wformat-security")
|
||||
#set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wmissing-format-attribute")
|
||||
|
||||
if (UNIX AND NOT WIN32)
|
||||
|
||||
# with -fPIC
|
||||
check_c_compiler_flag("-fPIC" WITH_FPIC)
|
||||
if (WITH_FPIC)
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fPIC")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fPIC")
|
||||
endif (WITH_FPIC)
|
||||
|
||||
endif(UNIX AND NOT WIN32)
|
||||
|
||||
check_c_compiler_flag_ssp("-fstack-protector" WITH_STACK_PROTECTOR)
|
||||
if (WITH_STACK_PROTECTOR)
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fstack-protector")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fstack-protector")
|
||||
set(CMAKE_MODULE_LINKER_FLAGS "${CMAKE_MODULE_LINKER_FLAGS} -fstack-protector")
|
||||
set(CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKDER_FLAGS} -fstack-protector")
|
||||
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKDER_FLAGS} -fstack-protector")
|
||||
endif (WITH_STACK_PROTECTOR)
|
||||
|
||||
check_c_compiler_flag("-D_FORTIFY_SOURCE=2" WITH_FORTIFY_SOURCE)
|
||||
if (WITH_FORTIFY_SOURCE)
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -D_FORTIFY_SOURCE=2")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -D_FORTIFY_SOURCE=2")
|
||||
endif (WITH_FORTIFY_SOURCE)
|
||||
endif (${CMAKE_C_COMPILER_ID} MATCHES GNU)
|
||||
|
||||
if (UNIX AND NOT WIN32)
|
||||
#
|
||||
# Check for large filesystem support
|
||||
#
|
||||
if (CMAKE_SIZEOF_VOID_P MATCHES "8")
|
||||
# with large file support
|
||||
execute_process(
|
||||
COMMAND
|
||||
getconf LFS64_CFLAGS
|
||||
OUTPUT_VARIABLE
|
||||
_lfs_CFLAGS
|
||||
ERROR_QUIET
|
||||
OUTPUT_STRIP_TRAILING_WHITESPACE
|
||||
)
|
||||
else (CMAKE_SIZEOF_VOID_P MATCHES "8")
|
||||
# with large file support
|
||||
execute_process(
|
||||
COMMAND
|
||||
getconf LFS_CFLAGS
|
||||
OUTPUT_VARIABLE
|
||||
_lfs_CFLAGS
|
||||
ERROR_QUIET
|
||||
OUTPUT_STRIP_TRAILING_WHITESPACE
|
||||
)
|
||||
endif (CMAKE_SIZEOF_VOID_P MATCHES "8")
|
||||
if (_lfs_CFLAGS)
|
||||
string(REGEX REPLACE "[\r\n]" " " "${_lfs_CFLAGS}" "${${_lfs_CFLAGS}}")
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${_lfs_CFLAGS}")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${_lfs_CFLAGS}")
|
||||
endif (_lfs_CFLAGS)
|
||||
|
||||
endif (UNIX AND NOT WIN32)
|
||||
|
||||
if (MSVC)
|
||||
# Use secure functions by defaualt and suppress warnings about
|
||||
#"deprecated" functions
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} /D _CRT_SECURE_CPP_OVERLOAD_STANDARD_NAMES=1")
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} /D _CRT_SECURE_CPP_OVERLOAD_STANDARD_NAMES_COUNT=1")
|
||||
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} /D _CRT_NONSTDC_NO_WARNINGS=1 /D _CRT_SECURE_NO_WARNINGS=1")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_C_FLAGS}")
|
||||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${CMAKE_C_FLAGS}")
|
||||
endif (MSVC)
|
||||
File diff suppressed because it is too large
Load Diff
@@ -1,26 +0,0 @@
|
||||
# - Check whether the C compiler supports a given flag in the
|
||||
# context of a stack checking compiler option.
|
||||
# CHECK_C_COMPILER_FLAG_SSP(FLAG VARIABLE)
|
||||
#
|
||||
# FLAG - the compiler flag
|
||||
# VARIABLE - variable to store the result
|
||||
#
|
||||
# This actually calls the check_c_source_compiles macro.
|
||||
# See help for CheckCSourceCompiles for a listing of variables
|
||||
# that can modify the build.
|
||||
|
||||
# Copyright (c) 2006, Alexander Neundorf, <neundorf@kde.org>
|
||||
#
|
||||
# Redistribution and use is allowed according to the terms of the BSD license.
|
||||
# For details see the accompanying COPYING-CMAKE-SCRIPTS file.
|
||||
|
||||
|
||||
INCLUDE(CheckCSourceCompiles)
|
||||
|
||||
MACRO (CHECK_C_COMPILER_FLAG_SSP _FLAG _RESULT)
|
||||
SET(SAFE_CMAKE_REQUIRED_DEFINITIONS "${CMAKE_REQUIRED_DEFINITIONS}")
|
||||
SET(CMAKE_REQUIRED_DEFINITIONS "${_FLAG}")
|
||||
CHECK_C_SOURCE_COMPILES("int main(int argc, char **argv) { char buffer[256]; return buffer[argc]=0;}" ${_RESULT})
|
||||
SET (CMAKE_REQUIRED_DEFINITIONS "${SAFE_CMAKE_REQUIRED_DEFINITIONS}")
|
||||
ENDMACRO (CHECK_C_COMPILER_FLAG_SSP)
|
||||
|
||||
@@ -1,19 +0,0 @@
|
||||
# - MACRO_ENSURE_OUT_OF_SOURCE_BUILD(<errorMessage>)
|
||||
# MACRO_ENSURE_OUT_OF_SOURCE_BUILD(<errorMessage>)
|
||||
|
||||
# Copyright (c) 2006, Alexander Neundorf, <neundorf@kde.org>
|
||||
#
|
||||
# Redistribution and use is allowed according to the terms of the BSD license.
|
||||
# For details see the accompanying COPYING-CMAKE-SCRIPTS file.
|
||||
|
||||
macro (MACRO_ENSURE_OUT_OF_SOURCE_BUILD _errorMessage)
|
||||
|
||||
string(COMPARE EQUAL "${CMAKE_SOURCE_DIR}" "${CMAKE_BINARY_DIR}" _insource)
|
||||
if (_insource)
|
||||
file(REMOVE [CMakeCache.txt CMakeFiles])
|
||||
message(FATAL_ERROR "${_errorMessage}")
|
||||
endif (_insource)
|
||||
|
||||
endmacro (MACRO_ENSURE_OUT_OF_SOURCE_BUILD)
|
||||
|
||||
# vim:ts=4:sw=4:expandtab
|
||||
@@ -1,19 +0,0 @@
|
||||
#!/usr/bin/python
|
||||
# Author: Lenna X. Peterson (github.com/lennax)
|
||||
# Based on bash script by James Goppert (github.com/jgoppert)
|
||||
#
|
||||
# script used to update cmake modules from git repo, can't make this
|
||||
# a submodule otherwise it won't know how to interpret the CMakeLists.txt
|
||||
# # # # # # subprocess# # # # # # # # # # # # # # # # # # # # # # # # # # # # # # # # # #
|
||||
|
||||
import os # for os.path
|
||||
import subprocess # for check_call()
|
||||
|
||||
clone_path = os.path.dirname(os.path.dirname(os.path.abspath(__file__)))
|
||||
print(clone_path)
|
||||
os.chdir(clone_path)
|
||||
subprocess.check_call(["git", "clone", "git://github.com/arktools/arkcmake.git","arkcmake_tmp"])
|
||||
subprocess.check_call(["rm", "-rf", "arkcmake_tmp/.git"])
|
||||
if os.path.isdir("arkcmake"):
|
||||
subprocess.check_call(["rm", "-rf", "arkcmake"])
|
||||
subprocess.check_call(["mv", "arkcmake_tmp", "arkcmake"])
|
||||
Binary file not shown.
|
Before Width: | Height: | Size: 25 KiB |
Binary file not shown.
|
Before Width: | Height: | Size: 34 KiB |
@@ -94,7 +94,11 @@
|
||||
"version": {
|
||||
"description": "Version number for the format of this file.",
|
||||
"type": "integer",
|
||||
"minimum": 1
|
||||
"minimum": 2
|
||||
},
|
||||
"translation": {
|
||||
"type": "object",
|
||||
"description": "This needs to match exactly with the content of actuators.translation.json"
|
||||
},
|
||||
"show-ui-if": {
|
||||
"$ref": "#/$defs/condition",
|
||||
|
||||
94
component_metadata/actuators.translation.json
Normal file
94
component_metadata/actuators.translation.json
Normal file
@@ -0,0 +1,94 @@
|
||||
{
|
||||
"translation": {
|
||||
"items": {
|
||||
"outputs_v1": {
|
||||
"list": {
|
||||
"key": "label",
|
||||
"items": {
|
||||
"subgroups": {
|
||||
"list": {
|
||||
"items": {
|
||||
"parameters": {
|
||||
"list": {
|
||||
"key": "name",
|
||||
"translate": [ "label" ]
|
||||
}
|
||||
},
|
||||
"per-channel-parameters": {
|
||||
"list": {
|
||||
"key": "name",
|
||||
"translate": [ "label" ]
|
||||
}
|
||||
},
|
||||
"channels": {
|
||||
"list": {
|
||||
"key": "param-index",
|
||||
"translate": [ "label" ]
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
},
|
||||
"functions_v1": {
|
||||
"items": {
|
||||
"*": {
|
||||
"translate": [ "label" ],
|
||||
"items": {
|
||||
"note": {
|
||||
"translate": [ "text" ]
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
},
|
||||
"mixer_v1": {
|
||||
"items": {
|
||||
"actuator-types": {
|
||||
"items": {
|
||||
"*": {
|
||||
"items": {
|
||||
"per-item-parameters": {
|
||||
"list": {
|
||||
"key": "name",
|
||||
"translate": [ "label" ]
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
},
|
||||
"config": {
|
||||
"list": {
|
||||
"key": "option",
|
||||
"translate": [ "title" ],
|
||||
"items": {
|
||||
"actuators": {
|
||||
"list": {
|
||||
"translate": [ "group-label", "item-label-prefix" ],
|
||||
"items": {
|
||||
"parameters": {
|
||||
"list": {
|
||||
"key": "name",
|
||||
"translate": [ "label" ]
|
||||
}
|
||||
},
|
||||
"per-item-parameters": {
|
||||
"list": {
|
||||
"key": "name",
|
||||
"translate": [ "label" ]
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -8,7 +8,11 @@
|
||||
"version": {
|
||||
"description": "Version number for the format of this file.",
|
||||
"type": "integer",
|
||||
"minimum": 1
|
||||
"minimum": 2
|
||||
},
|
||||
"translation": {
|
||||
"type": "object",
|
||||
"description": "This needs to match exactly with the content of parameter.translation.json"
|
||||
},
|
||||
"parameters": {
|
||||
"type": "array",
|
||||
|
||||
27
component_metadata/parameter.translation.json
Normal file
27
component_metadata/parameter.translation.json
Normal file
@@ -0,0 +1,27 @@
|
||||
{
|
||||
"translation": {
|
||||
"items": {
|
||||
"parameters": {
|
||||
"list": {
|
||||
"key": "name",
|
||||
"translate": [ "shortDesc", "longDesc" ],
|
||||
"translate-global": ["category", "group"],
|
||||
"items": {
|
||||
"bitmask": {
|
||||
"list": {
|
||||
"key": "index",
|
||||
"translate": [ "description" ]
|
||||
}
|
||||
},
|
||||
"values": {
|
||||
"list": {
|
||||
"key": "value",
|
||||
"translate": [ "description" ]
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
94
component_metadata/translation.schema.json
Normal file
94
component_metadata/translation.schema.json
Normal file
@@ -0,0 +1,94 @@
|
||||
{
|
||||
"$id": "https://mavlink.io/translation.schema.json",
|
||||
"$schema": "http://json-schema.org/draft-07/schema",
|
||||
"description": "Schema for translations (*.translation.json)",
|
||||
"type": "object",
|
||||
|
||||
"definitions": {
|
||||
"items": {
|
||||
"type": "object",
|
||||
|
||||
"patternProperties": {
|
||||
"^(\\*|[0-9a-zA-Z-_]+)$": {
|
||||
"comment": "Select individual attributes by name, or use '*' to match all",
|
||||
"type": "object",
|
||||
"properties": {
|
||||
"items": {
|
||||
"type": "object",
|
||||
"$ref": "#/definitions/items"
|
||||
},
|
||||
"$ref": {
|
||||
"type": "string",
|
||||
"comment": "Reference to one of the items in $defs (see below)",
|
||||
"pattern": "^#/\\$defs/"
|
||||
},
|
||||
"translate": {
|
||||
"type": "array",
|
||||
"items": {
|
||||
"type": "string",
|
||||
"description": "Object attribute to be translated. Might refer to a string or a list of strings."
|
||||
}
|
||||
},
|
||||
"translate-global": {
|
||||
"description": "Translate globally: this can be used for repeated strings, such as a category, which is then deduplicated and thus needs to be translated only once.",
|
||||
"type": "array",
|
||||
"items": {
|
||||
"type": "string",
|
||||
"description": "Object attribute to be translated. Might refer to a string or a list of strings."
|
||||
}
|
||||
},
|
||||
"list": {
|
||||
"type": "object",
|
||||
"properties": {
|
||||
"key": {
|
||||
"type": "string",
|
||||
"description": "Optionally specify a string/integer attribute that exists in each object of the list and uniquely identifies that object. If possible, specify a key. If not is specified, list indexes will be used (which may cause translation mismatch if elements are added/removed from the list)."
|
||||
},
|
||||
"items": {
|
||||
"type": "object",
|
||||
"$ref": "#/definitions/items"
|
||||
},
|
||||
"translate": {
|
||||
"type": "array",
|
||||
"items": {
|
||||
"type": "string",
|
||||
"description": "See above."
|
||||
}
|
||||
},
|
||||
"translate-global": {
|
||||
"type": "array",
|
||||
"items": {
|
||||
"type": "string",
|
||||
"description": "See above."
|
||||
}
|
||||
}
|
||||
},
|
||||
"additionalProperties": false
|
||||
}
|
||||
},
|
||||
"additionalProperties": false
|
||||
}
|
||||
},
|
||||
"additionalProperties": false
|
||||
}
|
||||
},
|
||||
|
||||
"properties": {
|
||||
"translation": {
|
||||
"type": "object",
|
||||
"properties": {
|
||||
"items": {
|
||||
"type": "object",
|
||||
"$ref": "#/definitions/items"
|
||||
},
|
||||
"$defs": {
|
||||
"comment": "Custom references (for recursive definitions). The keys in this dict can be used in a '$ref' as '#/$defs/<key>'",
|
||||
"$ref": "#/definitions/items"
|
||||
}
|
||||
},
|
||||
"required": [ "items" ],
|
||||
"additionalProperties": false
|
||||
}
|
||||
},
|
||||
"required": [ "translation" ]
|
||||
}
|
||||
@@ -1 +0,0 @@
|
||||
#define MAVLINK_VERSION "${PROJECT_VERSION}"
|
||||
11
examples/c/CMakeLists.txt
Normal file
11
examples/c/CMakeLists.txt
Normal file
@@ -0,0 +1,11 @@
|
||||
cmake_minimum_required(VERSION 3.13)
|
||||
|
||||
project(udp_example C)
|
||||
|
||||
set(CMAKE_C_STANDARD 11)
|
||||
|
||||
find_package(MAVLink REQUIRED)
|
||||
|
||||
add_executable(udp_example udp_example.c)
|
||||
|
||||
target_link_libraries(udp_example PRIVATE MAVLink::mavlink)
|
||||
22
examples/c/README.md
Normal file
22
examples/c/README.md
Normal file
@@ -0,0 +1,22 @@
|
||||
# Simple C example
|
||||
|
||||
Simple example receiving and sending MAVLink v2 over UDP based on POSIX APIs (e.g. Linux, BSD, macOS).
|
||||
|
||||
## Install MAVLink
|
||||
|
||||
In top level directory, build and install the MAVLink headers locally into the install folder:
|
||||
|
||||
```
|
||||
cmake -Bbuild -H. -DCMAKE_INSTALL_PREFIX=install
|
||||
cmake --build build --target install
|
||||
```
|
||||
|
||||
## Build example
|
||||
|
||||
In the example directory, build the example while passing the local install directory:
|
||||
|
||||
```
|
||||
cd examples/c
|
||||
cmake -Bbuild -H. -DCMAKE_PREFIX_PATH=$(pwd)/../../install
|
||||
cmake --build build
|
||||
```
|
||||
171
examples/c/udp_example.c
Normal file
171
examples/c/udp_example.c
Normal file
@@ -0,0 +1,171 @@
|
||||
// Simple example receiving and sending MAVLink v2 over UDP
|
||||
// based on POSIX APIs (e.g. Linux, BSD, macOS).
|
||||
|
||||
#include <errno.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include <arpa/inet.h>
|
||||
#include <netinet/in.h>
|
||||
#include <sys/socket.h>
|
||||
#include <time.h>
|
||||
|
||||
#include <mavlink/common/mavlink.h>
|
||||
|
||||
|
||||
void receive_some(int socket_fd, struct sockaddr_in* src_addr, socklen_t* src_addr_len, bool* src_addr_set);
|
||||
void handle_heartbeat(const mavlink_message_t* message);
|
||||
|
||||
void send_some(int socket_fd, const struct sockaddr_in* src_addr, socklen_t src_addr_len);
|
||||
void send_heartbeat(int socket_fd, const struct sockaddr_in* src_addr, socklen_t src_addr_len);
|
||||
|
||||
|
||||
int main(int argc, char* argv[])
|
||||
{
|
||||
// Open UDP socket
|
||||
const int socket_fd = socket(PF_INET, SOCK_DGRAM, 0);
|
||||
|
||||
if (socket_fd < 0) {
|
||||
printf("socket error: %s\n", strerror(errno));
|
||||
return -1;
|
||||
}
|
||||
|
||||
// Bind to port
|
||||
struct sockaddr_in addr = {};
|
||||
memset(&addr, 0, sizeof(addr));
|
||||
addr.sin_family = AF_INET;
|
||||
inet_pton(AF_INET, "0.0.0.0", &(addr.sin_addr)); // listen on all network interfaces
|
||||
addr.sin_port = htons(14550); // default port on the ground
|
||||
|
||||
if (bind(socket_fd, (struct sockaddr*)(&addr), sizeof(addr)) != 0) {
|
||||
printf("bind error: %s\n", strerror(errno));
|
||||
return -2;
|
||||
}
|
||||
|
||||
// We set a timeout at 100ms to prevent being stuck in recvfrom for too
|
||||
// long and missing our chance to send some stuff.
|
||||
struct timeval tv;
|
||||
tv.tv_sec = 0;
|
||||
tv.tv_usec = 100000;
|
||||
if (setsockopt(socket_fd, SOL_SOCKET, SO_RCVTIMEO, &tv, sizeof(tv)) < 0) {
|
||||
printf("setsockopt error: %s\n", strerror(errno));
|
||||
return -3;
|
||||
}
|
||||
|
||||
struct sockaddr_in src_addr = {};
|
||||
socklen_t src_addr_len = sizeof(src_addr);
|
||||
bool src_addr_set = false;
|
||||
|
||||
while (true) {
|
||||
// For illustration purposes we don't bother with threads or async here
|
||||
// and just interleave receiving and sending.
|
||||
// This only works if receive_some returns every now and then.
|
||||
receive_some(socket_fd, &src_addr, &src_addr_len, &src_addr_set);
|
||||
|
||||
if (src_addr_set) {
|
||||
send_some(socket_fd, &src_addr, src_addr_len);
|
||||
}
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void receive_some(int socket_fd, struct sockaddr_in* src_addr, socklen_t* src_addr_len, bool* src_addr_set)
|
||||
{
|
||||
// We just receive one UDP datagram and then return again.
|
||||
char buffer[2048]; // enough for MTU 1500 bytes
|
||||
|
||||
const int ret = recvfrom(
|
||||
socket_fd, buffer, sizeof(buffer), 0, (struct sockaddr*)(src_addr), src_addr_len);
|
||||
|
||||
if (ret < 0) {
|
||||
printf("recvfrom error: %s\n", strerror(errno));
|
||||
} else if (ret == 0) {
|
||||
// peer has done an orderly shutdown
|
||||
return;
|
||||
}
|
||||
|
||||
*src_addr_set = true;
|
||||
|
||||
mavlink_message_t message;
|
||||
mavlink_status_t status;
|
||||
for (int i = 0; i < ret; ++i) {
|
||||
if (mavlink_parse_char(MAVLINK_COMM_0, buffer[i], &message, &status) == 1) {
|
||||
|
||||
// printf(
|
||||
// "Received message %d from %d/%d\n",
|
||||
// message.msgid, message.sysid, message.compid);
|
||||
|
||||
switch (message.msgid) {
|
||||
case MAVLINK_MSG_ID_HEARTBEAT:
|
||||
handle_heartbeat(&message);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void handle_heartbeat(const mavlink_message_t* message)
|
||||
{
|
||||
mavlink_heartbeat_t heartbeat;
|
||||
mavlink_msg_heartbeat_decode(message, &heartbeat);
|
||||
|
||||
printf("Got heartbeat from ");
|
||||
switch (heartbeat.autopilot) {
|
||||
case MAV_AUTOPILOT_GENERIC:
|
||||
printf("generic");
|
||||
break;
|
||||
case MAV_AUTOPILOT_ARDUPILOTMEGA:
|
||||
printf("ArduPilot");
|
||||
break;
|
||||
case MAV_AUTOPILOT_PX4:
|
||||
printf("PX4");
|
||||
break;
|
||||
default:
|
||||
printf("other");
|
||||
break;
|
||||
}
|
||||
printf(" autopilot\n");
|
||||
}
|
||||
|
||||
void send_some(int socket_fd, const struct sockaddr_in* src_addr, socklen_t src_addr_len)
|
||||
{
|
||||
// Whenever a second has passed, we send a heartbeat.
|
||||
static time_t last_time = 0;
|
||||
time_t current_time = time(NULL);
|
||||
if (current_time - last_time >= 1) {
|
||||
send_heartbeat(socket_fd, src_addr, src_addr_len);
|
||||
last_time = current_time;
|
||||
}
|
||||
}
|
||||
|
||||
void send_heartbeat(int socket_fd, const struct sockaddr_in* src_addr, socklen_t src_addr_len)
|
||||
{
|
||||
mavlink_message_t message;
|
||||
|
||||
const uint8_t system_id = 42;
|
||||
const uint8_t base_mode = 0;
|
||||
const uint8_t custom_mode = 0;
|
||||
mavlink_msg_heartbeat_pack_chan(
|
||||
system_id,
|
||||
MAV_COMP_ID_PERIPHERAL,
|
||||
MAVLINK_COMM_0,
|
||||
&message,
|
||||
MAV_TYPE_GENERIC,
|
||||
MAV_AUTOPILOT_GENERIC,
|
||||
base_mode,
|
||||
custom_mode,
|
||||
MAV_STATE_STANDBY);
|
||||
|
||||
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
|
||||
const int len = mavlink_msg_to_send_buffer(buffer, &message);
|
||||
|
||||
int ret = sendto(socket_fd, buffer, len, 0, (const struct sockaddr*)src_addr, src_addr_len);
|
||||
if (ret != len) {
|
||||
printf("sendto error: %s\n", strerror(errno));
|
||||
} else {
|
||||
printf("Sent heartbeat\n");
|
||||
}
|
||||
}
|
||||
@@ -1,21 +0,0 @@
|
||||
# MAVLink UDP Quickstart Instructions
|
||||
|
||||
MAVLink UDP Example for *nix system (Linux, MacOS, BSD, etc.)
|
||||
|
||||
To compile with GCC, just enter:
|
||||
|
||||
```
|
||||
gcc -std=c99 -I ../../include/common -o mavlink_udp mavlink_udp.c
|
||||
```
|
||||
|
||||
The MAVLink header directory must be added to the include path, as shown above.
|
||||
Be sure to use version 2.0 of the MAVLink headers for this example
|
||||
as the example uses MAVLink 2 extension fields.
|
||||
|
||||
To run, type:
|
||||
|
||||
```
|
||||
./mavlink_udp
|
||||
```
|
||||
|
||||
If you run *QGroundControl* on the same machine, checkout received message in MAVLink Inspector widget.
|
||||
@@ -1,219 +0,0 @@
|
||||
/*******************************************************************************
|
||||
Copyright (C) 2010 Bryan Godbolt godbolt ( a t ) ualberta.ca
|
||||
|
||||
This program is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
This program is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
****************************************************************************/
|
||||
/*
|
||||
This program sends some data to qgroundcontrol using the mavlink protocol. The sent packets
|
||||
cause qgroundcontrol to respond with heartbeats. Any settings or custom commands sent from
|
||||
qgroundcontrol are printed by this program along with the heartbeats.
|
||||
|
||||
|
||||
I compiled this program successfully on Ubuntu 10.04 with the following command
|
||||
|
||||
gcc -I ../../pixhawk/mavlink/include -o udp-server udp-server-test.c
|
||||
|
||||
the rt library is needed for the clock_gettime on linux
|
||||
*/
|
||||
/* These headers are for QNX, but should all be standard on unix/linux */
|
||||
#include <stdio.h>
|
||||
#include <errno.h>
|
||||
#include <string.h>
|
||||
#include <sys/socket.h>
|
||||
#include <sys/types.h>
|
||||
#include <netinet/in.h>
|
||||
#include <unistd.h>
|
||||
#include <stdlib.h>
|
||||
#include <fcntl.h>
|
||||
#include <time.h>
|
||||
#if (defined __QNX__) | (defined __QNXNTO__)
|
||||
/* QNX specific headers */
|
||||
#include <unix.h>
|
||||
#else
|
||||
/* Linux / MacOS POSIX timer headers */
|
||||
#include <sys/time.h>
|
||||
#include <time.h>
|
||||
#include <arpa/inet.h>
|
||||
#include <stdbool.h> /* required for the definition of bool in C99 */
|
||||
#endif
|
||||
|
||||
/* This assumes you have the mavlink headers on your include path
|
||||
or in the same folder as this source file */
|
||||
#include <mavlink.h>
|
||||
|
||||
|
||||
#define BUFFER_LENGTH 2041 // minimum buffer size that can be used with qnx (I don't know why)
|
||||
|
||||
uint64_t microsSinceEpoch();
|
||||
|
||||
int main(int argc, char* argv[])
|
||||
{
|
||||
|
||||
char help[] = "--help";
|
||||
|
||||
|
||||
char target_ip[100];
|
||||
|
||||
float position[6] = {};
|
||||
int sock = socket(PF_INET, SOCK_DGRAM, IPPROTO_UDP);
|
||||
struct sockaddr_in gcAddr;
|
||||
struct sockaddr_in locAddr;
|
||||
//struct sockaddr_in fromAddr;
|
||||
uint8_t buf[BUFFER_LENGTH];
|
||||
ssize_t recsize;
|
||||
socklen_t fromlen = sizeof(gcAddr);
|
||||
int bytes_sent;
|
||||
mavlink_message_t msg;
|
||||
uint16_t len;
|
||||
int i = 0;
|
||||
//int success = 0;
|
||||
unsigned int temp = 0;
|
||||
|
||||
// Check if --help flag was used
|
||||
if ((argc == 2) && (strcmp(argv[1], help) == 0))
|
||||
{
|
||||
printf("\n");
|
||||
printf("\tUsage:\n\n");
|
||||
printf("\t");
|
||||
printf("%s", argv[0]);
|
||||
printf(" <ip address of QGroundControl>\n");
|
||||
printf("\tDefault for localhost: udp-server 127.0.0.1\n\n");
|
||||
exit(EXIT_FAILURE);
|
||||
}
|
||||
|
||||
|
||||
// Change the target ip if parameter was given
|
||||
strcpy(target_ip, "127.0.0.1");
|
||||
if (argc == 2)
|
||||
{
|
||||
strcpy(target_ip, argv[1]);
|
||||
}
|
||||
|
||||
|
||||
memset(&locAddr, 0, sizeof(locAddr));
|
||||
locAddr.sin_family = AF_INET;
|
||||
locAddr.sin_addr.s_addr = INADDR_ANY;
|
||||
locAddr.sin_port = htons(14551);
|
||||
|
||||
/* Bind the socket to port 14551 - necessary to receive packets from qgroundcontrol */
|
||||
if (-1 == bind(sock,(struct sockaddr *)&locAddr, sizeof(struct sockaddr)))
|
||||
{
|
||||
perror("error bind failed");
|
||||
close(sock);
|
||||
exit(EXIT_FAILURE);
|
||||
}
|
||||
|
||||
/* Attempt to make it non blocking */
|
||||
#if (defined __QNX__) | (defined __QNXNTO__)
|
||||
if (fcntl(sock, F_SETFL, O_NONBLOCK | FASYNC) < 0)
|
||||
#else
|
||||
if (fcntl(sock, F_SETFL, O_NONBLOCK | O_ASYNC) < 0)
|
||||
#endif
|
||||
|
||||
{
|
||||
fprintf(stderr, "error setting nonblocking: %s\n", strerror(errno));
|
||||
close(sock);
|
||||
exit(EXIT_FAILURE);
|
||||
}
|
||||
|
||||
|
||||
memset(&gcAddr, 0, sizeof(gcAddr));
|
||||
gcAddr.sin_family = AF_INET;
|
||||
gcAddr.sin_addr.s_addr = inet_addr(target_ip);
|
||||
gcAddr.sin_port = htons(14550);
|
||||
|
||||
|
||||
|
||||
for (;;)
|
||||
{
|
||||
|
||||
/*Send Heartbeat */
|
||||
mavlink_msg_heartbeat_pack(1, 200, &msg, MAV_TYPE_HELICOPTER, MAV_AUTOPILOT_GENERIC, MAV_MODE_GUIDED_ARMED, 0, MAV_STATE_ACTIVE);
|
||||
len = mavlink_msg_to_send_buffer(buf, &msg);
|
||||
bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in));
|
||||
|
||||
/* Send Status */
|
||||
mavlink_msg_sys_status_pack(1, 200, &msg, 0, 0, 0, 500, 11000, -1, -1, 0, 0, 0, 0, 0, 0, 0, 0, 0);
|
||||
len = mavlink_msg_to_send_buffer(buf, &msg);
|
||||
bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof (struct sockaddr_in));
|
||||
|
||||
/* Send Local Position */
|
||||
mavlink_msg_local_position_ned_pack(1, 200, &msg, microsSinceEpoch(),
|
||||
position[0], position[1], position[2],
|
||||
position[3], position[4], position[5]);
|
||||
len = mavlink_msg_to_send_buffer(buf, &msg);
|
||||
bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in));
|
||||
|
||||
/* Send attitude */
|
||||
mavlink_msg_attitude_pack(1, 200, &msg, microsSinceEpoch(), 1.2, 1.7, 3.14, 0.01, 0.02, 0.03);
|
||||
len = mavlink_msg_to_send_buffer(buf, &msg);
|
||||
bytes_sent = sendto(sock, buf, len, 0, (struct sockaddr*)&gcAddr, sizeof(struct sockaddr_in));
|
||||
|
||||
|
||||
memset(buf, 0, BUFFER_LENGTH);
|
||||
recsize = recvfrom(sock, (void *)buf, BUFFER_LENGTH, 0, (struct sockaddr *)&gcAddr, &fromlen);
|
||||
if (recsize > 0)
|
||||
{
|
||||
// Something received - print out all bytes and parse packet
|
||||
mavlink_message_t msg;
|
||||
mavlink_status_t status;
|
||||
|
||||
printf("Bytes Received: %d\nDatagram: ", (int)recsize);
|
||||
for (i = 0; i < recsize; ++i)
|
||||
{
|
||||
temp = buf[i];
|
||||
printf("%02x ", (unsigned char)temp);
|
||||
if (mavlink_parse_char(MAVLINK_COMM_0, buf[i], &msg, &status))
|
||||
{
|
||||
// Packet received
|
||||
printf("\nReceived packet: SYS: %d, COMP: %d, LEN: %d, MSG ID: %d\n", msg.sysid, msg.compid, msg.len, msg.msgid);
|
||||
}
|
||||
}
|
||||
printf("\n");
|
||||
}
|
||||
memset(buf, 0, BUFFER_LENGTH);
|
||||
sleep(1); // Sleep one second
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/* QNX timer version */
|
||||
#if (defined __QNX__) | (defined __QNXNTO__)
|
||||
uint64_t microsSinceEpoch()
|
||||
{
|
||||
|
||||
struct timespec time;
|
||||
|
||||
uint64_t micros = 0;
|
||||
|
||||
clock_gettime(CLOCK_REALTIME, &time);
|
||||
micros = (uint64_t)time.tv_sec * 1000000 + time.tv_nsec/1000;
|
||||
|
||||
return micros;
|
||||
}
|
||||
#else
|
||||
uint64_t microsSinceEpoch()
|
||||
{
|
||||
|
||||
struct timeval tv;
|
||||
|
||||
uint64_t micros = 0;
|
||||
|
||||
gettimeofday(&tv, NULL);
|
||||
micros = ((uint64_t)tv.tv_sec) * 1000000 + tv.tv_usec;
|
||||
|
||||
return micros;
|
||||
}
|
||||
#endif
|
||||
@@ -34,5 +34,14 @@
|
||||
commands: 50000 - 50099
|
||||
-->
|
||||
<include>cubepilot.xml</include>
|
||||
<!-- ras_a.xml range of IDs:
|
||||
messages: 51000 - 51999
|
||||
commands: 51000 - 51999
|
||||
https://github.com/Dronecode/air-iop-definitions/blob/master/message_definitions/v1.0/ras_a.xml
|
||||
-->
|
||||
<!--Next range to allocate range of IDs:
|
||||
messages: 52000 - ? < 60000
|
||||
commands: 52000 - ? < 60000
|
||||
-->
|
||||
<messages/>
|
||||
</mavlink>
|
||||
|
||||
@@ -2260,7 +2260,9 @@
|
||||
<param index="2" label="Immediate">Force immediate transition to the specified MAV_VTOL_STATE. 1: Force immediate, 0: normal transition. Can be used, for example, to trigger an emergency "Quadchute". Caution: Can be dangerous/damage vehicle, depending on autopilot implementation of this command.</param>
|
||||
</entry>
|
||||
<entry value="3001" name="MAV_CMD_ARM_AUTHORIZATION_REQUEST" hasLocation="false" isDestination="false">
|
||||
<description>Request authorization to arm the vehicle to a external entity, the arm authorizer is responsible to request all data that is needs from the vehicle before authorize or deny the request. If approved the progress of command_ack message should be set with period of time that this authorization is valid in seconds or in case it was denied it should be set with one of the reasons in ARM_AUTH_DENIED_REASON.
|
||||
<description>Request authorization to arm the vehicle to a external entity, the arm authorizer is responsible to request all data that is needs from the vehicle before authorize or deny the request.
|
||||
If approved the COMMAND_ACK message progress field should be set with period of time that this authorization is valid in seconds.
|
||||
If the authorization is denied COMMAND_ACK.result_param2 should be set with one of the reasons in ARM_AUTH_DENIED_REASON.
|
||||
</description>
|
||||
<param index="1" label="System ID" minValue="0" maxValue="255" increment="1">Vehicle system id, this way ground station can request arm authorization on behalf of any vehicle</param>
|
||||
</entry>
|
||||
@@ -2642,36 +2644,6 @@
|
||||
<description>Point toward of given id.</description>
|
||||
</entry>
|
||||
</enum>
|
||||
<enum name="MAV_CMD_ACK">
|
||||
<description>ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission.</description>
|
||||
<entry value="0" name="MAV_CMD_ACK_OK">
|
||||
<description>Command / mission item is ok.</description>
|
||||
</entry>
|
||||
<entry value="1" name="MAV_CMD_ACK_ERR_FAIL">
|
||||
<description>Generic error message if none of the other reasons fails or if no detailed error reporting is implemented.</description>
|
||||
</entry>
|
||||
<entry value="2" name="MAV_CMD_ACK_ERR_ACCESS_DENIED">
|
||||
<description>The system is refusing to accept this command from this source / communication partner.</description>
|
||||
</entry>
|
||||
<entry value="3" name="MAV_CMD_ACK_ERR_NOT_SUPPORTED">
|
||||
<description>Command or mission item is not supported, other commands would be accepted.</description>
|
||||
</entry>
|
||||
<entry value="4" name="MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED">
|
||||
<description>The coordinate frame of this command / mission item is not supported.</description>
|
||||
</entry>
|
||||
<entry value="5" name="MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE">
|
||||
<description>The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible.</description>
|
||||
</entry>
|
||||
<entry value="6" name="MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE">
|
||||
<description>The X or latitude value is out of range.</description>
|
||||
</entry>
|
||||
<entry value="7" name="MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE">
|
||||
<description>The Y or longitude value is out of range.</description>
|
||||
</entry>
|
||||
<entry value="8" name="MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE">
|
||||
<description>The Z or altitude value is out of range.</description>
|
||||
</entry>
|
||||
</enum>
|
||||
<enum name="MAV_PARAM_TYPE">
|
||||
<description>Specifies the datatype of a MAVLink parameter.</description>
|
||||
<entry value="1" name="MAV_PARAM_TYPE_UINT8">
|
||||
@@ -3220,7 +3192,7 @@
|
||||
<entry value="3" name="MAV_BATTERY_FUNCTION_AVIONICS">
|
||||
<description>Avionics battery</description>
|
||||
</entry>
|
||||
<entry value="4" name="MAV_BATTERY_TYPE_PAYLOAD">
|
||||
<entry value="4" name="MAV_BATTERY_FUNCTION_PAYLOAD">
|
||||
<description>Payload battery</description>
|
||||
</entry>
|
||||
</enum>
|
||||
@@ -3781,6 +3753,9 @@
|
||||
<entry value="3" name="ZOOM_TYPE_FOCAL_LENGTH">
|
||||
<description>Zoom value/variable focal length in millimetres. Note that there is no message to get the valid zoom range of the camera, so this can type can only be used for cameras where the zoom range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera)</description>
|
||||
</entry>
|
||||
<entry value="4" name="ZOOM_TYPE_HORIZONTAL_FOV">
|
||||
<description>Zoom value as horizontal field of view in degrees.</description>
|
||||
</entry>
|
||||
</enum>
|
||||
<enum name="SET_FOCUS_TYPE">
|
||||
<description>Focus types for MAV_CMD_SET_CAMERA_FOCUS</description>
|
||||
@@ -4510,12 +4485,12 @@
|
||||
<entry value="60" name="AIS_TYPE_PASSENGER"/>
|
||||
<entry value="61" name="AIS_TYPE_PASSENGER_HAZARDOUS_A"/>
|
||||
<entry value="62" name="AIS_TYPE_PASSENGER_HAZARDOUS_B"/>
|
||||
<entry value="63" name="AIS_TYPE_AIS_TYPE_PASSENGER_HAZARDOUS_C"/>
|
||||
<entry value="63" name="AIS_TYPE_PASSENGER_HAZARDOUS_C"/>
|
||||
<entry value="64" name="AIS_TYPE_PASSENGER_HAZARDOUS_D"/>
|
||||
<entry value="65" name="AIS_TYPE_PASSENGER_RESERVED_1"/>
|
||||
<entry value="66" name="AIS_TYPE_PASSENGER_RESERVED_2"/>
|
||||
<entry value="67" name="AIS_TYPE_PASSENGER_RESERVED_3"/>
|
||||
<entry value="68" name="AIS_TYPE_AIS_TYPE_PASSENGER_RESERVED_4"/>
|
||||
<entry value="68" name="AIS_TYPE_PASSENGER_RESERVED_4"/>
|
||||
<entry value="69" name="AIS_TYPE_PASSENGER_UNKNOWN"/>
|
||||
<entry value="70" name="AIS_TYPE_CARGO"/>
|
||||
<entry value="71" name="AIS_TYPE_CARGO_HAZARDOUS_A"/>
|
||||
@@ -5302,7 +5277,7 @@
|
||||
</description>
|
||||
<field type="uint16_t" name="seq">Sequence</field>
|
||||
<extensions/>
|
||||
<field type="uint16_t" name="total" invalid="UINT16_MAX">Total number of mission items. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.</field>
|
||||
<field type="uint16_t" name="total" invalid="UINT16_MAX">Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle.</field>
|
||||
<field type="uint8_t" name="mission_state" enum="MISSION_STATE" invalid="0">Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported.</field>
|
||||
<field type="uint8_t" name="mission_mode" invalid="0">Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode).</field>
|
||||
</message>
|
||||
@@ -5556,7 +5531,7 @@
|
||||
<field type="float" name="climb" units="m/s">Current climb rate.</field>
|
||||
</message>
|
||||
<message id="75" name="COMMAND_INT">
|
||||
<description>Message encoding a command with parameters as scaled integers. Scaling depends on the actual command value. NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). The command microservice is documented at https://mavlink.io/en/services/command.html</description>
|
||||
<description>Send a command with up to seven parameters to the MAV, where params 5 and 6 are integers and the other values are floats. This is preferred over COMMAND_LONG as it allows the MAV_FRAME to be specified for interpreting positional information, such as altitude. COMMAND_INT is also preferred when sending latitude and longitude data in params 5 and 6, as it allows for greater precision. Param 5 and 6 encode positional data as scaled integers, where the scaling depends on the actual command value. NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). The command microservice is documented at https://mavlink.io/en/services/command.html</description>
|
||||
<field type="uint8_t" name="target_system">System ID</field>
|
||||
<field type="uint8_t" name="target_component">Component ID</field>
|
||||
<field type="uint8_t" name="frame" enum="MAV_FRAME">The coordinate system of the COMMAND.</field>
|
||||
@@ -5572,7 +5547,7 @@
|
||||
<field type="float" name="z" invalid="NaN">PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame).</field>
|
||||
</message>
|
||||
<message id="76" name="COMMAND_LONG">
|
||||
<description>Send a command with up to seven parameters to the MAV. The command microservice is documented at https://mavlink.io/en/services/command.html</description>
|
||||
<description>Send a command with up to seven parameters to the MAV. COMMAND_INT is generally preferred when sending MAV_CMD commands that include positional information; it offers higher precision and allows the MAV_FRAME to be specified (which may otherwise be ambiguous, particularly for altitude). The command microservice is documented at https://mavlink.io/en/services/command.html</description>
|
||||
<field type="uint8_t" name="target_system">System which should execute the command</field>
|
||||
<field type="uint8_t" name="target_component">Component which should execute the command, 0 for all components</field>
|
||||
<field type="uint16_t" name="command" enum="MAV_CMD">Command ID (of command to send).</field>
|
||||
@@ -6427,6 +6402,7 @@
|
||||
<field type="float" name="pt_compensation">Pressure/temperature compensation</field>
|
||||
<extensions/>
|
||||
<field type="float" name="ignition_voltage" units="V">Supply voltage to EFI sparking system. Zero in this value means "unknown", so if the supply voltage really is zero volts use 0.0001 instead.</field>
|
||||
<field type="float" name="fuel_pressure" units="kPa">Fuel pressure. Zero in this value means "unknown", so if the fuel pressure really is zero kPa use 0.0001 instead.</field>
|
||||
</message>
|
||||
<!-- MESSAGE IDs 180 - 229: Space for custom messages in individual projectname_messages.xml files -->
|
||||
<message id="230" name="ESTIMATOR_STATUS">
|
||||
@@ -6936,8 +6912,6 @@
|
||||
<field type="float" name="angular_velocity_z" units="rad/s" invalid="NaN">Z component of angular velocity, positive is yawing to the right, NaN to be ignored.</field>
|
||||
</message>
|
||||
<message id="283" name="GIMBAL_DEVICE_INFORMATION">
|
||||
<wip/>
|
||||
<!-- This message is work-in-progress and it can therefore change. It should NOT be used in stable production environments. -->
|
||||
<description>Information about a low level gimbal. This message should be requested by the gimbal manager or a ground station using MAV_CMD_REQUEST_MESSAGE. The maximum angles and rates are the limits by hardware. However, the limits by software used are likely different/smaller and dependent on mode/settings/etc..</description>
|
||||
<field type="uint32_t" name="time_boot_ms" units="ms">Timestamp (time since system boot).</field>
|
||||
<field type="char[32]" name="vendor_name">Name of the gimbal vendor.</field>
|
||||
@@ -6956,8 +6930,6 @@
|
||||
<field type="float" name="yaw_max" units="rad" invalid="NaN">Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.</field>
|
||||
</message>
|
||||
<message id="284" name="GIMBAL_DEVICE_SET_ATTITUDE">
|
||||
<wip/>
|
||||
<!-- This message is work-in-progress and it can therefore change. It should NOT be used in stable production environments. -->
|
||||
<description>Low level message to control a gimbal device's attitude.
|
||||
This message is to be sent from the gimbal manager to the gimbal device component.
|
||||
The quaternion and angular velocities can be set to NaN according to use case.
|
||||
@@ -6979,8 +6951,6 @@
|
||||
<field type="float" name="angular_velocity_z" units="rad/s" invalid="NaN">Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN to be ignored.</field>
|
||||
</message>
|
||||
<message id="285" name="GIMBAL_DEVICE_ATTITUDE_STATUS">
|
||||
<wip/>
|
||||
<!-- This message is work-in-progress and it can therefore change. It should NOT be used in stable production environments. -->
|
||||
<description>Message reporting the status of a gimbal device.
|
||||
This message should be broadcast by a gimbal device component at a low regular rate (e.g. 5 Hz).
|
||||
For the angles encoded in the quaternion and the angular velocities holds:
|
||||
@@ -7010,8 +6980,6 @@
|
||||
<field type="float" name="delta_yaw_velocity" units="rad/s" invalid="NAN">Yaw angular velocity relating the angular velocities in earth and body frames (see message description). NaN if unknown.</field>
|
||||
</message>
|
||||
<message id="286" name="AUTOPILOT_STATE_FOR_GIMBAL_DEVICE">
|
||||
<wip/>
|
||||
<!-- This message is work-in-progress and it can therefore change. It should NOT be used in stable production environments. -->
|
||||
<description>Low level message containing autopilot state relevant for a gimbal device. This message is to be sent from the autopilot to the gimbal device component. The data of this message are for the gimbal device's estimator corrections, in particular horizon compensation, as well as indicates autopilot control intentions, e.g. feed forward angular control in the z-axis.</description>
|
||||
<field type="uint8_t" name="target_system">System ID</field>
|
||||
<field type="uint8_t" name="target_component">Component ID</field>
|
||||
@@ -7481,6 +7449,7 @@
|
||||
<field type="uint16_t" name="sequence_oldest_available">Oldest Sequence number that is still available after the sequence set in REQUEST_EVENT.</field>
|
||||
<field type="uint8_t" name="reason" enum="MAV_EVENT_ERROR_REASON">Error reason.</field>
|
||||
</message>
|
||||
<!-- The message ids 510 and 511 are reserved for ABSOLUTE_TARGET and RELATIVE_TARGET, currently in development.xml. -->
|
||||
<message id="387" name="CANFD_FRAME">
|
||||
<description>A forwarded CANFD frame as requested by MAV_CMD_CAN_FORWARD. These are separated from CAN_FRAME as they need different handling (eg. TAO handling)</description>
|
||||
<field type="uint8_t" name="target_system">System ID.</field>
|
||||
|
||||
@@ -336,6 +336,40 @@
|
||||
<param index="6" reserved="true" default="0"/>
|
||||
<param index="7" reserved="true" default="NaN"/>
|
||||
</entry>
|
||||
<entry value="550" name="MAV_CMD_SET_AT_S_PARAM" hasLocation="false" isDestination="false">
|
||||
<description>Allows setting an AT S command of an SiK radio.
|
||||
</description>
|
||||
<param index="1" label="Radio instance">The radio instance, one-based, 0 for all.</param>
|
||||
<param index="2" label="Index">The Sx index, e.g. 3 for S3 which is NETID.</param>
|
||||
<param index="3" label="Value">The value to set it to, e.g. default 25 for NETID</param>
|
||||
<param index="4" reserved="true"/>
|
||||
<param index="5" reserved="true"/>
|
||||
<param index="6" reserved="true"/>
|
||||
<param index="7" reserved="true"/>
|
||||
</entry>
|
||||
</enum>
|
||||
<enum name="TARGET_ABSOLUTE_SENSOR_CAPABILITY_FLAGS" bitmask="true">
|
||||
<description>These flags indicate the sensor reporting capabilities for TARGET_ABSOLUTE.</description>
|
||||
<entry value="1" name="TARGET_ABSOLUTE_SENSOR_CAPABILITY_POSITION"/>
|
||||
<entry value="2" name="TARGET_ABSOLUTE_SENSOR_CAPABILITY_VELOCITY"/>
|
||||
<entry value="4" name="TARGET_ABSOLUTE_SENSOR_CAPABILITY_ACCELERATION"/>
|
||||
<entry value="8" name="TARGET_ABSOLUTE_SENSOR_CAPABILITY_ATTITUDE"/>
|
||||
<entry value="16" name="TARGET_ABSOLUTE_SENSOR_CAPABILITY_RATES"/>
|
||||
</enum>
|
||||
<enum name="TARGET_OBS_FRAME">
|
||||
<description>The frame of a target observation from an onboard sensor.</description>
|
||||
<entry value="0" name="TARGET_OBS_FRAME_LOCAL_NED">
|
||||
<description>NED local tangent frame (x: North, y: East, z: Down) with origin fixed relative to earth.</description>
|
||||
</entry>
|
||||
<entry value="1" name="TARGET_OBS_FRAME_BODY_FRD">
|
||||
<description>FRD local frame aligned to the vehicle's attitude (x: Forward, y: Right, z: Down) with an origin that travels with vehicle.</description>
|
||||
</entry>
|
||||
<entry value="2" name="TARGET_OBS_FRAME_LOCAL_OFFSET_NED">
|
||||
<description>NED local tangent frame (x: North, y: East, z: Down) with an origin that travels with vehicle.</description>
|
||||
</entry>
|
||||
<entry value="3" name="TARGET_OBS_FRAME_OTHER">
|
||||
<description>Other sensor frame for target observations neither in local NED nor in body FRD.</description>
|
||||
</entry>
|
||||
</enum>
|
||||
</enums>
|
||||
<messages>
|
||||
@@ -459,5 +493,37 @@
|
||||
<field type="uint8_t" name="base_mode" enum="MAV_MODE_FLAG" display="bitmask">System mode bitmap.</field>
|
||||
<field type="uint32_t" name="custom_mode">A bitfield for use for autopilot-specific flags</field>
|
||||
</message>
|
||||
<!-- Target info from a sensor on the target -->
|
||||
<message id="510" name="TARGET_ABSOLUTE">
|
||||
<description>Current motion information from sensors on a target</description>
|
||||
<field type="uint64_t" name="timestamp" units="us">Timestamp (UNIX epoch time).</field>
|
||||
<field type="uint8_t" name="id">The ID of the target if multiple targets are present</field>
|
||||
<field type="uint8_t" name="sensor_capabilities" enum="TARGET_ABSOLUTE_SENSOR_CAPABILITY_FLAGS" display="bitmask">Bitmap to indicate the sensor's reporting capabilities</field>
|
||||
<field type="int32_t" name="lat" units="degE7">Target's latitude (WGS84)</field>
|
||||
<field type="int32_t" name="lon" units="degE7">Target's longitude (WGS84)</field>
|
||||
<field type="float" name="alt" units="m">Target's altitude (AMSL)</field>
|
||||
<field type="float[3]" name="vel" units="m/s" invalid="[0]">Target's velocity in its body frame</field>
|
||||
<field type="float[3]" name="acc" units="m/s/s" invalid="[0]">Linear target's acceleration in its body frame</field>
|
||||
<field type="float[4]" name="q_target" invalid="[0]">Quaternion of the target's orientation from its body frame to the vehicle's NED frame.</field>
|
||||
<field type="float[3]" name="rates" units="rad/s" invalid="[0]">Target's roll, pitch and yaw rates</field>
|
||||
<field type="float[2]" name="position_std" units="m">Standard deviation of horizontal (eph) and vertical (epv) position errors</field>
|
||||
<field type="float[3]" name="vel_std" units="m/s">Standard deviation of the target's velocity in its body frame</field>
|
||||
<field type="float[3]" name="acc_std" units="m/s/s">Standard deviation of the target's acceleration in its body frame</field>
|
||||
</message>
|
||||
<!-- Target info measured by MAV's onboard sensors -->
|
||||
<message id="511" name="TARGET_RELATIVE">
|
||||
<description>The location of a target measured by MAV's onboard sensors. </description>
|
||||
<field type="uint64_t" name="timestamp" units="us">Timestamp (UNIX epoch time)</field>
|
||||
<field type="uint8_t" name="id" instance="true">The ID of the target if multiple targets are present</field>
|
||||
<field type="uint8_t" name="frame" enum="TARGET_OBS_FRAME">Coordinate frame used for following fields.</field>
|
||||
<field type="float" name="x" units="m">X Position of the target in TARGET_OBS_FRAME</field>
|
||||
<field type="float" name="y" units="m">Y Position of the target in TARGET_OBS_FRAME</field>
|
||||
<field type="float" name="z" units="m">Z Position of the target in TARGET_OBS_FRAME</field>
|
||||
<field type="float[3]" name="pos_std" units="m">Standard deviation of the target's position in TARGET_OBS_FRAME</field>
|
||||
<field type="float" name="yaw_std" units="rad">Standard deviation of the target's orientation in TARGET_OBS_FRAME</field>
|
||||
<field type="float[4]" name="q_target">Quaternion of the target's orientation from the target's frame to the TARGET_OBS_FRAME (w, x, y, z order, zero-rotation is 1, 0, 0, 0)</field>
|
||||
<field type="float[4]" name="q_sensor">Quaternion of the sensor's orientation from TARGET_OBS_FRAME to vehicle-carried NED. (Ignored if set to (0,0,0,0)) (w, x, y, z order, zero-rotation is 1, 0, 0, 0)</field>
|
||||
<field type="uint8_t" name="type" enum="LANDING_TARGET_TYPE">Type of target</field>
|
||||
</message>
|
||||
</messages>
|
||||
</mavlink>
|
||||
|
||||
@@ -7,9 +7,10 @@ Contact:
|
||||
Range of IDs:
|
||||
messages: 60000 - 60049
|
||||
commands: 60000 - 60049
|
||||
Documentation:
|
||||
Documentation:
|
||||
STORM32 and QSHOT additions
|
||||
6. Okt. 2021
|
||||
with mLRS additions merged
|
||||
3. Feb. 2023
|
||||
All messages are technically WIP, but some are quite stable now.
|
||||
Quite stable means that it is in practical use, but may see extension.
|
||||
A more detailed description of the concept underlying the STORM32 and QSHOT messages can be found here:
|
||||
@@ -18,52 +19,41 @@ Documentation:
|
||||
<mavlink>
|
||||
<include>ardupilotmega.xml</include>
|
||||
<version>1</version>
|
||||
<dialect>0</dialect>
|
||||
<!--
|
||||
STORM32 enums
|
||||
-->
|
||||
<dialect>1</dialect>
|
||||
<enums>
|
||||
<!-- #############################
|
||||
STORM32 enums
|
||||
############################# -->
|
||||
<!-- ***************************
|
||||
STORM32 tunnel enum, this is merely a redefinition for convennience
|
||||
*************************** -->
|
||||
<enum name="MAV_STORM32_TUNNEL_PAYLOAD_TYPE">
|
||||
<!-- Stable -->
|
||||
<entry value="200" name="MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH1_IN">
|
||||
<description>Registered for STorM32 gimbal controller.</description>
|
||||
<description>Registered for STorM32 gimbal controller. For communication with gimbal or camera.</description>
|
||||
</entry>
|
||||
<entry value="201" name="MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH1_OUT">
|
||||
<description>Registered for STorM32 gimbal controller.</description>
|
||||
<description>Registered for STorM32 gimbal controller. For communication with gimbal or camera.</description>
|
||||
</entry>
|
||||
<entry value="202" name="MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH2_IN">
|
||||
<description>Registered for STorM32 gimbal controller.</description>
|
||||
<description>Registered for STorM32 gimbal controller. For communication with gimbal.</description>
|
||||
</entry>
|
||||
<entry value="203" name="MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH2_OUT">
|
||||
<description>Registered for STorM32 gimbal controller.</description>
|
||||
<description>Registered for STorM32 gimbal controller. For communication with gimbal.</description>
|
||||
</entry>
|
||||
<entry value="204" name="MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH3_IN">
|
||||
<description>Registered for STorM32 gimbal controller.</description>
|
||||
<description>Registered for STorM32 gimbal controller. For communication with camera.</description>
|
||||
</entry>
|
||||
<entry value="205" name="MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH3_OUT">
|
||||
<description>Registered for STorM32 gimbal controller.</description>
|
||||
</entry>
|
||||
<entry value="206" name="MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED6">
|
||||
<description>Registered for STorM32 gimbal controller.</description>
|
||||
</entry>
|
||||
<entry value="207" name="MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED7">
|
||||
<description>Registered for STorM32 gimbal controller.</description>
|
||||
</entry>
|
||||
<entry value="208" name="MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED8">
|
||||
<description>Registered for STorM32 gimbal controller.</description>
|
||||
</entry>
|
||||
<entry value="209" name="MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED9">
|
||||
<description>Registered for STorM32 gimbal controller.</description>
|
||||
<description>Registered for STorM32 gimbal controller. For communication with camera.</description>
|
||||
</entry>
|
||||
</enum>
|
||||
<!-- ***************************
|
||||
STORM32 gimbal prearm check flags
|
||||
COMPONENT_PREARM_STATUS deprecated 7.Dez.2022, the PREARM_FLAGS enums are kept however for convenience
|
||||
*************************** -->
|
||||
<enum name="MAV_STORM32_GIMBAL_PREARM_FLAGS" bitmask="true">
|
||||
<!-- Quite stable -->
|
||||
<!-- Stable -->
|
||||
<description>STorM32 gimbal prearm check flags.</description>
|
||||
<entry value="1" name="MAV_STORM32_GIMBAL_PREARM_FLAGS_IS_NORMAL">
|
||||
<description>STorM32 gimbal is in normal state.</description>
|
||||
@@ -81,7 +71,7 @@ Documentation:
|
||||
<description>A battery voltage is applied and is in range.</description>
|
||||
</entry>
|
||||
<entry value="32" name="MAV_STORM32_GIMBAL_PREARM_FLAGS_VIRTUALCHANNELS_RECEIVING">
|
||||
<description>???.</description>
|
||||
<description>Virtual input channels are receiving data.</description>
|
||||
</entry>
|
||||
<entry value="64" name="MAV_STORM32_GIMBAL_PREARM_FLAGS_MAVLINK_RECEIVING">
|
||||
<description>Mavlink messages are being received.</description>
|
||||
@@ -114,121 +104,9 @@ Documentation:
|
||||
</enum>
|
||||
<!-- ***************************
|
||||
STORM32 gimbal device enums
|
||||
deprecated 21.Nov.2022, replaced by gimbal protocol v2 flags
|
||||
removed to force migration
|
||||
*************************** -->
|
||||
<enum name="MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS" bitmask="true">
|
||||
<!-- Quite stable -->
|
||||
<description>Gimbal device capability flags.</description>
|
||||
<entry value="1" name="MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT">
|
||||
<description>Gimbal device supports a retracted position.</description>
|
||||
</entry>
|
||||
<entry value="2" name="MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL">
|
||||
<description>Gimbal device supports a horizontal, forward looking position, stabilized. Can also be used to reset the gimbal's orientation.</description>
|
||||
</entry>
|
||||
<entry value="4" name="MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS">
|
||||
<description>Gimbal device supports rotating around roll axis.</description>
|
||||
</entry>
|
||||
<entry value="8" name="MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW">
|
||||
<description>Gimbal device supports to follow a roll angle relative to the vehicle.</description>
|
||||
</entry>
|
||||
<entry value="16" name="MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK">
|
||||
<description>Gimbal device supports locking to an roll angle (generally that's the default).</description>
|
||||
</entry>
|
||||
<entry value="32" name="MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS">
|
||||
<description>Gimbal device supports rotating around pitch axis.</description>
|
||||
</entry>
|
||||
<entry value="64" name="MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW">
|
||||
<description>Gimbal device supports to follow a pitch angle relative to the vehicle.</description>
|
||||
</entry>
|
||||
<entry value="128" name="MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK">
|
||||
<description>Gimbal device supports locking to an pitch angle (generally that's the default).</description>
|
||||
</entry>
|
||||
<entry value="256" name="MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS">
|
||||
<description>Gimbal device supports rotating around yaw axis.</description>
|
||||
</entry>
|
||||
<entry value="512" name="MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW">
|
||||
<description>Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default).</description>
|
||||
</entry>
|
||||
<entry value="1024" name="MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK">
|
||||
<description>Gimbal device supports locking to a heading angle.</description>
|
||||
</entry>
|
||||
<entry value="2048" name="MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_INFINITE_YAW">
|
||||
<description>Gimbal device supports yawing/panning infinitely (e.g. using a slip ring).</description>
|
||||
</entry>
|
||||
<entry value="65536" name="MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_ABSOLUTE_YAW">
|
||||
<description>Gimbal device supports absolute yaw angles (this usually requires support by an autopilot, and can be dynamic, i.e., go on and off during runtime).</description>
|
||||
</entry>
|
||||
<entry value="131072" name="MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS_HAS_RC">
|
||||
<description>Gimbal device supports control via an RC input signal.</description>
|
||||
</entry>
|
||||
</enum>
|
||||
<enum name="MAV_STORM32_GIMBAL_DEVICE_FLAGS" bitmask="true">
|
||||
<!-- Quite stable -->
|
||||
<description>Flags for gimbal device operation. Used for setting and reporting, unless specified otherwise. Settings which are in violation of the capability flags are ignored by the gimbal device.</description>
|
||||
<entry value="1" name="MAV_STORM32_GIMBAL_DEVICE_FLAGS_RETRACT">
|
||||
<description>Retracted safe position (no stabilization), takes presedence over NEUTRAL flag. If supported by the gimbal, the angles in the retracted position can be set in addition.</description>
|
||||
</entry>
|
||||
<entry value="2" name="MAV_STORM32_GIMBAL_DEVICE_FLAGS_NEUTRAL">
|
||||
<description>Neutral position (horizontal, forward looking, with stabiliziation).</description>
|
||||
</entry>
|
||||
<entry value="4" name="MAV_STORM32_GIMBAL_DEVICE_FLAGS_ROLL_LOCK">
|
||||
<description>Lock roll angle to absolute angle relative to horizon (not relative to drone). This is generally the default.</description>
|
||||
</entry>
|
||||
<entry value="8" name="MAV_STORM32_GIMBAL_DEVICE_FLAGS_PITCH_LOCK">
|
||||
<description>Lock pitch angle to absolute angle relative to horizon (not relative to drone). This is generally the default.</description>
|
||||
</entry>
|
||||
<entry value="16" name="MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_LOCK">
|
||||
<description>Lock yaw angle to absolute angle relative to earth (not relative to drone). When the YAW_ABSOLUTE flag is set, the quaternion is in the Earth frame with the x-axis pointing North (yaw absolute), else it is in the Earth frame rotated so that the x-axis is pointing forward (yaw relative to vehicle).</description>
|
||||
</entry>
|
||||
<entry value="256" name="MAV_STORM32_GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_ABSOLUTE">
|
||||
<description>Gimbal device can accept absolute yaw angle input. This flag cannot be set, is only for reporting (attempts to set it are rejected by the gimbal device).</description>
|
||||
</entry>
|
||||
<entry value="512" name="MAV_STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE">
|
||||
<description>Yaw angle is absolute (is only accepted if CAN_ACCEPT_YAW_ABSOLUTE is set). If this flag is set, the quaternion is in the Earth frame with the x-axis pointing North (yaw absolute), else it is in the Earth frame rotated so that the x-axis is pointing forward (yaw relative to vehicle).</description>
|
||||
</entry>
|
||||
<entry value="1024" name="MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE">
|
||||
<description>RC control. The RC input signal fed to the gimbal device exclusively controls the gimbal's orientation. Overrides RC_MIXED flag if that is also set.</description>
|
||||
</entry>
|
||||
<entry value="2048" name="MAV_STORM32_GIMBAL_DEVICE_FLAGS_RC_MIXED">
|
||||
<description>RC control. The RC input signal fed to the gimbal device is mixed into the gimbal's orientation. Is overridden by RC_EXCLUSIVE flag if that is also set.</description>
|
||||
</entry>
|
||||
<entry value="65535" name="MAV_STORM32_GIMBAL_DEVICE_FLAGS_NONE">
|
||||
<description>UINT16_MAX = ignore.</description>
|
||||
</entry>
|
||||
</enum>
|
||||
<enum name="MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS" bitmask="true">
|
||||
<!-- Quite stable -->
|
||||
<description>Gimbal device error and condition flags (0 means no error or other condition).</description>
|
||||
<entry value="1" name="MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT">
|
||||
<description>Gimbal device is limited by hardware roll limit.</description>
|
||||
</entry>
|
||||
<entry value="2" name="MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT">
|
||||
<description>Gimbal device is limited by hardware pitch limit.</description>
|
||||
</entry>
|
||||
<entry value="4" name="MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT">
|
||||
<description>Gimbal device is limited by hardware yaw limit.</description>
|
||||
</entry>
|
||||
<entry value="8" name="MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR">
|
||||
<description>There is an error with the gimbal device's encoders.</description>
|
||||
</entry>
|
||||
<entry value="16" name="MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR">
|
||||
<description>There is an error with the gimbal device's power source.</description>
|
||||
</entry>
|
||||
<entry value="32" name="MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR">
|
||||
<description>There is an error with the gimbal device's motors.</description>
|
||||
</entry>
|
||||
<entry value="64" name="MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR">
|
||||
<description>There is an error with the gimbal device's software.</description>
|
||||
</entry>
|
||||
<entry value="128" name="MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR">
|
||||
<description>There is an error with the gimbal device's communication.</description>
|
||||
</entry>
|
||||
<entry value="256" name="MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING">
|
||||
<description>Gimbal device is currently calibrating (not an error).</description>
|
||||
</entry>
|
||||
<entry value="32768" name="MAV_STORM32_GIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER">
|
||||
<description>Gimbal device is not assigned to a gimbal manager (not an error).</description>
|
||||
</entry>
|
||||
</enum>
|
||||
<!-- ***************************
|
||||
STORM32 gimbal manager enums
|
||||
*************************** -->
|
||||
@@ -238,13 +116,10 @@ Documentation:
|
||||
<entry value="1" name="MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS_HAS_PROFILES">
|
||||
<description>The gimbal manager supports several profiles.</description>
|
||||
</entry>
|
||||
<entry value="2" name="MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_CHANGE">
|
||||
<description>The gimbal manager supports changing the gimbal manager during run time, i.e. can be enabled/disabled.</description>
|
||||
</entry>
|
||||
</enum>
|
||||
<enum name="MAV_STORM32_GIMBAL_MANAGER_FLAGS" bitmask="true">
|
||||
<!-- Quite stable -->
|
||||
<description>Flags for gimbal manager operation. Used for setting and reporting, unless specified otherwise. If a setting is accepted by the gimbal manager, is reported in the STORM32_GIMBAL_MANAGER_STATUS message.</description>
|
||||
<!-- Stable, may grow however -->
|
||||
<description>Flags for gimbal manager operation. Used for setting and reporting, unless specified otherwise. If a setting has been accepted by the gimbal manager is reported in the STORM32_GIMBAL_MANAGER_STATUS message.</description>
|
||||
<entry value="0" name="MAV_STORM32_GIMBAL_MANAGER_FLAGS_NONE">
|
||||
<description>0 = ignore.</description>
|
||||
</entry>
|
||||
@@ -283,7 +158,7 @@ Documentation:
|
||||
</entry>
|
||||
</enum>
|
||||
<enum name="MAV_STORM32_GIMBAL_MANAGER_CLIENT">
|
||||
<!-- Quite stable -->
|
||||
<!-- Stable, may grow however -->
|
||||
<description>Gimbal manager client ID. In a prioritizing profile, the priorities are determined by the implementation; they could e.g. be custom1 > onboard > GCS > autopilot/camera > GCS2 > custom2.</description>
|
||||
<entry value="0" name="MAV_STORM32_GIMBAL_MANAGER_CLIENT_NONE">
|
||||
<description>For convenience.</description>
|
||||
@@ -313,56 +188,33 @@ Documentation:
|
||||
<description>This is the custom2 client.</description>
|
||||
</entry>
|
||||
</enum>
|
||||
<enum name="MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS" bitmask="true">
|
||||
<!-- WIP -->
|
||||
<description>Flags for gimbal manager set up. Used for setting and reporting, unless specified otherwise.</description>
|
||||
<entry value="16384" name="MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS_ENABLE">
|
||||
<description>Enable gimbal manager. This flag is only for setting, is not reported.</description>
|
||||
</entry>
|
||||
<entry value="32768" name="MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS_DISABLE">
|
||||
<description>Disable gimbal manager. This flag is only for setting, is not reported.</description>
|
||||
</entry>
|
||||
</enum>
|
||||
<enum name="MAV_STORM32_GIMBAL_MANAGER_PROFILE">
|
||||
<!-- WIP -->
|
||||
<description>Gimbal manager profiles. Only standard profiles are defined. Any implementation can define it's own profile in addition, and should use enum values > 16.</description>
|
||||
<description>Gimbal manager profiles. Only standard profiles are defined. Any implementation can define its own profile(s) in addition, and should use enum values > 16.</description>
|
||||
<entry value="0" name="MAV_STORM32_GIMBAL_MANAGER_PROFILE_DEFAULT">
|
||||
<description>Default profile. Implementation specific.</description>
|
||||
</entry>
|
||||
<entry value="1" name="MAV_STORM32_GIMBAL_MANAGER_PROFILE_CUSTOM">
|
||||
<description>Custom profile. Configurable profile according to the STorM32 definition. Is configured with STORM32_GIMBAL_MANAGER_PROFIL.</description>
|
||||
<description>Not supported/deprecated.</description>
|
||||
</entry>
|
||||
<entry value="2" name="MAV_STORM32_GIMBAL_MANAGER_PROFILE_COOPERATIVE">
|
||||
<description>Default cooperative profile. Uses STorM32 custom profile with default settings to achieve cooperative behavior.</description>
|
||||
<description>Profile with cooperative behavior.</description>
|
||||
</entry>
|
||||
<entry value="3" name="MAV_STORM32_GIMBAL_MANAGER_PROFILE_EXCLUSIVE">
|
||||
<description>Default exclusive profile. Uses STorM32 custom profile with default settings to achieve exclusive behavior.</description>
|
||||
<description>Profile with exclusive behavior.</description>
|
||||
</entry>
|
||||
<entry value="4" name="MAV_STORM32_GIMBAL_MANAGER_PROFILE_PRIORITY_COOPERATIVE">
|
||||
<description>Default priority profile with cooperative behavior for equal priority. Uses STorM32 custom profile with default settings to achieve priority-based behavior.</description>
|
||||
<description>Profile with priority and cooperative behavior for equal priority.</description>
|
||||
</entry>
|
||||
<entry value="5" name="MAV_STORM32_GIMBAL_MANAGER_PROFILE_PRIORITY_EXCLUSIVE">
|
||||
<description>Default priority profile with exclusive behavior for equal priority. Uses STorM32 custom profile with default settings to achieve priority-based behavior.</description>
|
||||
</entry>
|
||||
</enum>
|
||||
<enum name="MAV_STORM32_GIMBAL_ACTION">
|
||||
<!-- WIP -->
|
||||
<description>Gimbal actions.</description>
|
||||
<entry value="1" name="MAV_STORM32_GIMBAL_ACTION_RECENTER">
|
||||
<description>Trigger the gimbal device to recenter the gimbal.</description>
|
||||
</entry>
|
||||
<entry value="2" name="MAV_STORM32_GIMBAL_ACTION_CALIBRATION">
|
||||
<description>Trigger the gimbal device to run a calibration.</description>
|
||||
</entry>
|
||||
<entry value="3" name="MAV_STORM32_GIMBAL_ACTION_DISCOVER_MANAGER">
|
||||
<description>Trigger gimbal device to (re)discover the gimbal manager during run time.</description>
|
||||
<description>Profile with priority and exclusive behavior for equal priority.</description>
|
||||
</entry>
|
||||
</enum>
|
||||
<!-- ***************************
|
||||
QSHOT manager mode enums
|
||||
*************************** -->
|
||||
<enum name="MAV_QSHOT_MODE">
|
||||
<!-- Quite stable, will grow however -->
|
||||
<!-- Quite stable, may grow however -->
|
||||
<description>Enumeration of possible shot modes.</description>
|
||||
<entry value="0" name="MAV_QSHOT_MODE_UNDEFINED">
|
||||
<description>Undefined shot mode. Can be used to determine if qshots should be used or not.</description>
|
||||
@@ -399,34 +251,25 @@ Documentation:
|
||||
STORM32 and QSHOT cmds
|
||||
*************************** -->
|
||||
<enum name="MAV_CMD">
|
||||
<!-- leave room for 60000 gimbal device configure -->
|
||||
<!-- leave room for 60001 gimbal manager configure -->
|
||||
<entry value="60002" name="MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW" hasLocation="false" isDestination="false">
|
||||
<!-- Quite stable -->
|
||||
<!-- Stable -->
|
||||
<description>Command to a gimbal manager to control the gimbal tilt and pan angles. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. A gimbal device is never to react to this command.</description>
|
||||
<param index="1" label="Pitch angle" units="deg" minValue="-180" maxValue="180">Pitch/tilt angle (positive: tilt up, NaN to be ignored).</param>
|
||||
<param index="2" label="Yaw angle" units="deg" minValue="-180" maxValue="180">Yaw/pan angle (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored).</param>
|
||||
<param index="3" label="Pitch rate" units="deg/s">Pitch/tilt rate (positive: tilt up, NaN to be ignored).</param>
|
||||
<param index="4" label="Yaw rate" units="deg/s">Yaw/pan rate (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored).</param>
|
||||
<param index="5" label="Gimbal device flags" enum="MAV_STORM32_GIMBAL_DEVICE_FLAGS">Gimbal device flags.</param>
|
||||
<param index="6" label="Gimbal manager flags" enum="MAV_STORM32_GIMBAL_MANAGER_FLAGS">Gimbal manager flags.</param>
|
||||
<param index="7" label="Gimbal ID and client ID">Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals). The client is copied into bits 8-15.</param>
|
||||
<param index="1" label="Pitch angle" units="deg" minValue="-180" maxValue="180">Pitch/tilt angle (positive: tilt up). NaN to be ignored.</param>
|
||||
<param index="2" label="Yaw angle" units="deg" minValue="-180" maxValue="180">Yaw/pan angle (positive: pan to the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.</param>
|
||||
<param index="3" label="Pitch rate" units="deg/s">Pitch/tilt rate (positive: tilt up). NaN to be ignored.</param>
|
||||
<param index="4" label="Yaw rate" units="deg/s">Yaw/pan rate (positive: pan to the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.</param>
|
||||
<param index="5" label="Gimbal device flags" enum="GIMBAL_DEVICE_FLAGS">Gimbal device flags to be applied.</param>
|
||||
<param index="6" label="Gimbal manager flags" enum="MAV_STORM32_GIMBAL_MANAGER_FLAGS">Gimbal manager flags to be applied.</param>
|
||||
<param index="7" label="Gimbal ID and client">Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals. The client is copied into bits 8-15.</param>
|
||||
</entry>
|
||||
<entry value="60010" name="MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP" hasLocation="false" isDestination="false">
|
||||
<wip/>
|
||||
<!-- WIP -->
|
||||
<description>Command to configure a gimbal manager. A gimbal device is never to react to this command. The selected profile is reported in the STORM32_GIMBAL_MANAGER_STATUS message.</description>
|
||||
<param index="1" label="Profile" enum="MAV_STORM32_GIMBAL_MANAGER_PROFILE">Gimbal manager profile (0 = default).</param>
|
||||
<param index="2" label="Setup flags" enum="MAV_STORM32_GIMBAL_MANAGER_SETUP_FLAGS">Gimbal manager setup flags (0 = none).</param>
|
||||
<param index="7" label="Gimbal ID">Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.</param>
|
||||
</entry>
|
||||
<entry value="60011" name="MAV_CMD_STORM32_DO_GIMBAL_ACTION" hasLocation="false" isDestination="false">
|
||||
<wip/>
|
||||
<!-- WIP -->
|
||||
<description>Command to initiate gimbal actions. Usually performed by the gimbal device, but some can also be done by the gimbal manager. It is hence best to broadcast this command.</description>
|
||||
<param index="1" label="Action" enum="MAV_STORM32_GIMBAL_ACTION">Gimbal action to initiate (0 = none).</param>
|
||||
<param index="7" label="Gimbal ID">Gimbal ID of the gimbal to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.</param>
|
||||
</entry>
|
||||
<entry value="60020" name="MAV_CMD_QSHOT_DO_CONFIGURE" hasLocation="false" isDestination="false">
|
||||
<wip/>
|
||||
<!-- WIP -->
|
||||
@@ -435,115 +278,98 @@ Documentation:
|
||||
<param index="2" label="Shot state or command">Set shot state or command. The allowed values are specific to the selected shot mode.</param>
|
||||
</entry>
|
||||
</enum>
|
||||
<!-- #############################
|
||||
mLRS enums
|
||||
############################# -->
|
||||
<enum name="RADIO_RC_CHANNELS_FLAGS" bitmask="true">
|
||||
<description>RADIO_RC_CHANNELS flags (bitmask).</description>
|
||||
<entry value="1" name="RADIO_RC_CHANNELS_FLAGS_FAILSAFE">
|
||||
<description>Failsafe is active.</description>
|
||||
</entry>
|
||||
<entry value="2" name="RADIO_RC_CHANNELS_FLAGS_FRAME_MISSED">
|
||||
<description>Indicates that the current frame has not been received. Channel values are frozen.</description>
|
||||
</entry>
|
||||
</enum>
|
||||
<enum name="RADIO_LINK_STATS_FLAGS" bitmask="true">
|
||||
<description>RADIO_LINK_STATS flags (bitmask).</description>
|
||||
<entry value="1" name="RADIO_LINK_STATS_FLAGS_RSSI_DBM">
|
||||
<description>Rssi are in negative dBm. Values 0..254 corresponds to 0..-254 dBm.</description>
|
||||
</entry>
|
||||
</enum>
|
||||
</enums>
|
||||
<!--
|
||||
STORM32 messages
|
||||
-->
|
||||
<messages>
|
||||
<!-- #############################
|
||||
STORM32 messages
|
||||
############################# -->
|
||||
<!-- ***************************
|
||||
STORM32 gimbal device messages
|
||||
deprecated 21.Nov.2022, replaced by gimbal protocol v2 gimbal device messages
|
||||
removed to force migration
|
||||
*************************** -->
|
||||
<!-- leave room for 60000 gimbal device information -->
|
||||
<message id="60001" name="STORM32_GIMBAL_DEVICE_STATUS">
|
||||
<!-- Quite stable -->
|
||||
<description>Message reporting the current status of a gimbal device. This message should be broadcasted by a gimbal device component at a low regular rate (e.g. 4 Hz). For higher rates it should be emitted with a target.</description>
|
||||
<field type="uint8_t" name="target_system">System ID</field>
|
||||
<field type="uint8_t" name="target_component">Component ID</field>
|
||||
<field type="uint32_t" name="time_boot_ms" units="ms">Timestamp (time since system boot).</field>
|
||||
<field type="uint16_t" name="flags" enum="MAV_STORM32_GIMBAL_DEVICE_FLAGS">Gimbal device flags currently applied.</field>
|
||||
<field type="float[4]" name="q">Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame depends on the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag.</field>
|
||||
<field type="float" name="angular_velocity_x" units="rad/s" invalid="NaN">X component of angular velocity (NaN if unknown).</field>
|
||||
<field type="float" name="angular_velocity_y" units="rad/s" invalid="NaN">Y component of angular velocity (NaN if unknown).</field>
|
||||
<field type="float" name="angular_velocity_z" units="rad/s" invalid="NaN">Z component of angular velocity (the frame depends on the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN if unknown).</field>
|
||||
<field type="float" name="yaw_absolute" units="deg" invalid="NaN">Yaw in absolute frame relative to Earth's North, north is 0 (NaN if unknown).</field>
|
||||
<field type="uint16_t" name="failure_flags" display="bitmask" enum="GIMBAL_DEVICE_ERROR_FLAGS">Failure flags (0 for no failure).</field>
|
||||
</message>
|
||||
<message id="60002" name="STORM32_GIMBAL_DEVICE_CONTROL">
|
||||
<!-- Quite stable -->
|
||||
<description>Message to a gimbal device to control its attitude. This message is to be sent from the gimbal manager to the gimbal device. Angles and rates can be set to NaN according to use case.</description>
|
||||
<field type="uint8_t" name="target_system">System ID</field>
|
||||
<field type="uint8_t" name="target_component">Component ID</field>
|
||||
<field type="uint16_t" name="flags" enum="MAV_STORM32_GIMBAL_DEVICE_FLAGS" invalid="UINT16_MAX">Gimbal device flags (UINT16_MAX to be ignored).</field>
|
||||
<field type="float[4]" name="q" invalid="[NaN:]">Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, set first element to NaN to be ignored).</field>
|
||||
<field type="float" name="angular_velocity_x" units="rad/s" invalid="NaN">X component of angular velocity (positive: roll to the right, NaN to be ignored).</field>
|
||||
<field type="float" name="angular_velocity_y" units="rad/s" invalid="NaN">Y component of angular velocity (positive: tilt up, NaN to be ignored).</field>
|
||||
<field type="float" name="angular_velocity_z" units="rad/s" invalid="NaN">Z component of angular velocity (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored).</field>
|
||||
</message>
|
||||
<!-- ***************************
|
||||
STORM32 gimbal manager messages
|
||||
*************************** -->
|
||||
revised 27.Nov.2022, to account for usage of gimbal protocol v2 gimbal device messages/commands/flags
|
||||
STORM32_GIMBAL_MANAGER_PROFILE removed, MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP gets the job done
|
||||
*************************** -->
|
||||
<message id="60010" name="STORM32_GIMBAL_MANAGER_INFORMATION">
|
||||
<!-- Quite stable, may grow however -->
|
||||
<description>Information about a gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE. It mirrors some fields of the STORM32_GIMBAL_DEVICE_INFORMATION message, but not all. If the additional information is desired, also STORM32_GIMBAL_DEVICE_INFORMATION should be requested.</description>
|
||||
<!-- Stable, may grow however -->
|
||||
<description>Information about a gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE. It mirrors some fields of the GIMBAL_DEVICE_INFORMATION message, but not all. If the additional information is desired, also GIMBAL_DEVICE_INFORMATION should be requested.</description>
|
||||
<field type="uint8_t" name="gimbal_id" instance="true">Gimbal ID (component ID or 1-6 for non-MAVLink gimbal) that this gimbal manager is responsible for.</field>
|
||||
<field type="uint32_t" name="device_cap_flags" enum="MAV_STORM32_GIMBAL_DEVICE_CAP_FLAGS" display="bitmask">Gimbal device capability flags.</field>
|
||||
<field type="uint32_t" name="device_cap_flags" enum="GIMBAL_DEVICE_CAP_FLAGS" display="bitmask">Gimbal device capability flags. Same flags as reported by GIMBAL_DEVICE_INFORMATION. The flag is only 16 bit wide, but stored in 32 bit, for backwards compatibility (high word is zero).</field>
|
||||
<field type="uint32_t" name="manager_cap_flags" enum="MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS" display="bitmask">Gimbal manager capability flags.</field>
|
||||
<field type="float" name="roll_min" units="rad" invalid="NaN">Hardware minimum roll angle (positive: roll to the right, NaN if unknown).</field>
|
||||
<field type="float" name="roll_max" units="rad" invalid="NaN">Hardware maximum roll angle (positive: roll to the right, NaN if unknown).</field>
|
||||
<field type="float" name="pitch_min" units="rad" invalid="NaN">Hardware minimum pitch/tilt angle (positive: tilt up, NaN if unknown).</field>
|
||||
<field type="float" name="pitch_max" units="rad" invalid="NaN">Hardware maximum pitch/tilt angle (positive: tilt up, NaN if unknown).</field>
|
||||
<field type="float" name="yaw_min" units="rad" invalid="NaN">Hardware minimum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base, NaN if unknown).</field>
|
||||
<field type="float" name="yaw_max" units="rad" invalid="NaN">Hardware maximum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base, NaN if unknown).</field>
|
||||
<field type="float" name="roll_min" units="rad" invalid="NaN">Hardware minimum roll angle (positive: roll to the right). NaN if unknown.</field>
|
||||
<field type="float" name="roll_max" units="rad" invalid="NaN">Hardware maximum roll angle (positive: roll to the right). NaN if unknown.</field>
|
||||
<field type="float" name="pitch_min" units="rad" invalid="NaN">Hardware minimum pitch/tilt angle (positive: tilt up). NaN if unknown.</field>
|
||||
<field type="float" name="pitch_max" units="rad" invalid="NaN">Hardware maximum pitch/tilt angle (positive: tilt up). NaN if unknown.</field>
|
||||
<field type="float" name="yaw_min" units="rad" invalid="NaN">Hardware minimum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base). NaN if unknown.</field>
|
||||
<field type="float" name="yaw_max" units="rad" invalid="NaN">Hardware maximum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base). NaN if unknown.</field>
|
||||
</message>
|
||||
<message id="60011" name="STORM32_GIMBAL_MANAGER_STATUS">
|
||||
<!-- Quite stable, may grow however -->
|
||||
<!-- Stable, may grow however -->
|
||||
<description>Message reporting the current status of a gimbal manager. This message should be broadcast at a low regular rate (e.g. 1 Hz, may be increase momentarily to e.g. 5 Hz for a period of 1 sec after a change).</description>
|
||||
<field type="uint8_t" name="gimbal_id" instance="true">Gimbal ID (component ID or 1-6 for non-MAVLink gimbal) that this gimbal manager is responsible for.</field>
|
||||
<field type="uint8_t" name="supervisor" enum="MAV_STORM32_GIMBAL_MANAGER_CLIENT">Client who is currently supervisor (0 = none).</field>
|
||||
<field type="uint16_t" name="device_flags" enum="MAV_STORM32_GIMBAL_DEVICE_FLAGS">Gimbal device flags currently applied.</field>
|
||||
<field type="uint16_t" name="device_flags" enum="GIMBAL_DEVICE_FLAGS">Gimbal device flags currently applied. Same flags as reported by GIMBAL_DEVICE_ATTITUDE_STATUS.</field>
|
||||
<field type="uint16_t" name="manager_flags" enum="MAV_STORM32_GIMBAL_MANAGER_FLAGS">Gimbal manager flags currently applied.</field>
|
||||
<field type="uint8_t" name="profile" enum="MAV_STORM32_GIMBAL_MANAGER_PROFILE">Profile currently applied (0 = default).</field>
|
||||
</message>
|
||||
<message id="60012" name="STORM32_GIMBAL_MANAGER_CONTROL">
|
||||
<!-- Quite stable -->
|
||||
<!-- Stable -->
|
||||
<description>Message to a gimbal manager to control the gimbal attitude. Angles and rates can be set to NaN according to use case. A gimbal device is never to react to this message.</description>
|
||||
<field type="uint8_t" name="target_system">System ID</field>
|
||||
<field type="uint8_t" name="target_component">Component ID</field>
|
||||
<field type="uint8_t" name="gimbal_id" instance="true">Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals).</field>
|
||||
<field type="uint8_t" name="gimbal_id" instance="true">Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.</field>
|
||||
<field type="uint8_t" name="client" enum="MAV_STORM32_GIMBAL_MANAGER_CLIENT">Client which is contacting the gimbal manager (must be set).</field>
|
||||
<field type="uint16_t" name="device_flags" enum="MAV_STORM32_GIMBAL_DEVICE_FLAGS" invalid="UINT16_MAX">Gimbal device flags (UINT16_MAX to be ignored).</field>
|
||||
<field type="uint16_t" name="manager_flags" enum="MAV_STORM32_GIMBAL_MANAGER_FLAGS" invalid="0">Gimbal manager flags (0 to be ignored).</field>
|
||||
<field type="float[4]" name="q" invalid="[NaN:]">Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is determined by the GIMBAL_MANAGER_FLAGS_ABSOLUTE_YAW flag, set first element to NaN to be ignored).</field>
|
||||
<field type="float" name="angular_velocity_x" units="rad/s" invalid="NaN">X component of angular velocity (positive: roll to the right, NaN to be ignored).</field>
|
||||
<field type="float" name="angular_velocity_y" units="rad/s" invalid="NaN">Y component of angular velocity (positive: tilt up, NaN to be ignored).</field>
|
||||
<field type="float" name="angular_velocity_z" units="rad/s" invalid="NaN">Z component of angular velocity (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored).</field>
|
||||
<field type="uint16_t" name="device_flags" enum="GIMBAL_DEVICE_FLAGS" invalid="UINT16_MAX">Gimbal device flags to be applied (UINT16_MAX to be ignored). Same flags as used in GIMBAL_DEVICE_SET_ATTITUDE.</field>
|
||||
<field type="uint16_t" name="manager_flags" enum="MAV_STORM32_GIMBAL_MANAGER_FLAGS" invalid="0">Gimbal manager flags to be applied (0 to be ignored).</field>
|
||||
<field type="float[4]" name="q" invalid="[NaN:]">Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). Set first element to NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.</field>
|
||||
<field type="float" name="angular_velocity_x" units="rad/s" invalid="NaN">X component of angular velocity (positive: roll to the right). NaN to be ignored.</field>
|
||||
<field type="float" name="angular_velocity_y" units="rad/s" invalid="NaN">Y component of angular velocity (positive: tilt up). NaN to be ignored.</field>
|
||||
<field type="float" name="angular_velocity_z" units="rad/s" invalid="NaN">Z component of angular velocity (positive: pan to the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.</field>
|
||||
</message>
|
||||
<message id="60013" name="STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW">
|
||||
<!-- Quite stable -->
|
||||
<!-- Stable -->
|
||||
<description>Message to a gimbal manager to control the gimbal tilt and pan angles. Angles and rates can be set to NaN according to use case. A gimbal device is never to react to this message.</description>
|
||||
<field type="uint8_t" name="target_system">System ID</field>
|
||||
<field type="uint8_t" name="target_component">Component ID</field>
|
||||
<field type="uint8_t" name="gimbal_id" instance="true">Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals).</field>
|
||||
<field type="uint8_t" name="gimbal_id" instance="true">Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.</field>
|
||||
<field type="uint8_t" name="client" enum="MAV_STORM32_GIMBAL_MANAGER_CLIENT">Client which is contacting the gimbal manager (must be set).</field>
|
||||
<field type="uint16_t" name="device_flags" enum="MAV_STORM32_GIMBAL_DEVICE_FLAGS" invalid="UINT16_MAX">Gimbal device flags (UINT16_MAX to be ignored).</field>
|
||||
<field type="uint16_t" name="manager_flags" enum="MAV_STORM32_GIMBAL_MANAGER_FLAGS" invalid="0">Gimbal manager flags (0 to be ignored).</field>
|
||||
<field type="float" name="pitch" units="rad" invalid="NaN">Pitch/tilt angle (positive: tilt up, NaN to be ignored).</field>
|
||||
<field type="float" name="yaw" units="rad" invalid="NaN">Yaw/pan angle (positive: pan the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored).</field>
|
||||
<field type="float" name="pitch_rate" units="rad/s" invalid="NaN">Pitch/tilt angular rate (positive: tilt up, NaN to be ignored).</field>
|
||||
<field type="float" name="yaw_rate" units="rad/s" invalid="NaN">Yaw/pan angular rate (positive: pan to the right, the frame is determined by the STORM32_GIMBAL_DEVICE_FLAGS_YAW_ABSOLUTE flag, NaN to be ignored).</field>
|
||||
<field type="uint16_t" name="device_flags" enum="GIMBAL_DEVICE_FLAGS" invalid="UINT16_MAX">Gimbal device flags to be applied (UINT16_MAX to be ignored). Same flags as used in GIMBAL_DEVICE_SET_ATTITUDE.</field>
|
||||
<field type="uint16_t" name="manager_flags" enum="MAV_STORM32_GIMBAL_MANAGER_FLAGS" invalid="0">Gimbal manager flags to be applied (0 to be ignored).</field>
|
||||
<field type="float" name="pitch" units="rad" invalid="NaN">Pitch/tilt angle (positive: tilt up). NaN to be ignored.</field>
|
||||
<field type="float" name="yaw" units="rad" invalid="NaN">Yaw/pan angle (positive: pan the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.</field>
|
||||
<field type="float" name="pitch_rate" units="rad/s" invalid="NaN">Pitch/tilt angular rate (positive: tilt up). NaN to be ignored.</field>
|
||||
<field type="float" name="yaw_rate" units="rad/s" invalid="NaN">Yaw/pan angular rate (positive: pan to the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.</field>
|
||||
</message>
|
||||
<message id="60014" name="STORM32_GIMBAL_MANAGER_CORRECT_ROLL">
|
||||
<!-- Quite stable -->
|
||||
<description>Message to a gimbal manager to correct the gimbal roll angle. This message is typically used to manually correct for a tilted horizon in operation. A gimbal device is never to react to this message.</description>
|
||||
<field type="uint8_t" name="target_system">System ID</field>
|
||||
<field type="uint8_t" name="target_component">Component ID</field>
|
||||
<field type="uint8_t" name="gimbal_id" instance="true">Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals).</field>
|
||||
<field type="uint8_t" name="gimbal_id" instance="true">Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.</field>
|
||||
<field type="uint8_t" name="client" enum="MAV_STORM32_GIMBAL_MANAGER_CLIENT">Client which is contacting the gimbal manager (must be set).</field>
|
||||
<field type="float" name="roll" units="rad">Roll angle (positive to roll to the right).</field>
|
||||
</message>
|
||||
<message id="60015" name="STORM32_GIMBAL_MANAGER_PROFILE">
|
||||
<wip/>
|
||||
<!-- WIP -->
|
||||
<description>Message to set a gimbal manager profile. A gimbal device is never to react to this command. The selected profile is reported in the STORM32_GIMBAL_MANAGER_STATUS message.</description>
|
||||
<field type="uint8_t" name="target_system">System ID</field>
|
||||
<field type="uint8_t" name="target_component">Component ID</field>
|
||||
<field type="uint8_t" name="gimbal_id" instance="true">Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals, send command multiple times for more than one but not all gimbals).</field>
|
||||
<field type="uint8_t" name="profile" enum="MAV_STORM32_GIMBAL_MANAGER_PROFILE">Profile to be applied (0 = default).</field>
|
||||
<field type="uint8_t[8]" name="priorities">Priorities for custom profile.</field>
|
||||
<field type="uint8_t" name="profile_flags">Profile flags for custom profile (0 = default).</field>
|
||||
<field type="uint8_t" name="rc_timeout">Rc timeouts for custom profile (0 = infinite, in uints of 100 ms).</field>
|
||||
<field type="uint8_t[8]" name="timeouts">Timeouts for custom profile (0 = infinite, in uints of 100 ms).</field>
|
||||
</message>
|
||||
<!-- ***************************
|
||||
QSHOT manager messages
|
||||
*************************** -->
|
||||
@@ -556,14 +382,52 @@ Documentation:
|
||||
</message>
|
||||
<!-- ***************************
|
||||
General messages
|
||||
COMPONENT_PREARM_STATUS deprecated 7.Dez.2022, replaced by events micro service, removed to force migration
|
||||
*************************** -->
|
||||
<message id="60025" name="COMPONENT_PREARM_STATUS">
|
||||
<!-- Quite stable -->
|
||||
<description>Message reporting the status of the prearm checks. The flags are component specific.</description>
|
||||
<field type="uint8_t" name="target_system">System ID</field>
|
||||
<field type="uint8_t" name="target_component">Component ID</field>
|
||||
<field type="uint32_t" name="enabled_flags" invalid="UINT32_MAX">Currently enabled prearm checks. 0 means no checks are being performed, UINT32_MAX means not known.</field>
|
||||
<field type="uint32_t" name="fail_flags">Currently not passed prearm checks. 0 means all checks have been passed.</field>
|
||||
<!-- #############################
|
||||
mLRS messages
|
||||
############################# -->
|
||||
<message id="60045" name="RADIO_RC_CHANNELS">
|
||||
<description>Radio channels. Supports up to 24 channels. Channel values are in centerd 13 bit format. Range is [-4096,4096], center is 0. Conversion to PWM is x * 5/32 + 1500. Should be emitted only by components with component id MAV_COMP_ID_TELEMETRY_RADIO.</description>
|
||||
<field type="uint8_t" name="count">Total number of RC channels being received. This can be larger than 24, indicating that more channels are available but not given in this message.</field>
|
||||
<field type="uint8_t" name="flags" enum="RADIO_RC_CHANNELS_FLAGS" display="bitmask">Radio channels status flags.</field>
|
||||
<extensions/>
|
||||
<field type="int16_t[24]" name="channels">RC channels. Channels above count should be set to 0, to benefit from MAVLink's zero padding.</field>
|
||||
</message>
|
||||
<message id="60046" name="RADIO_LINK_STATS">
|
||||
<description>Radio link statistics. Should be emitted only by components with component id MAV_COMP_ID_TELEMETRY_RADIO. Per default, rssi values are in MAVLink units: 0 represents weakest signal, 254 represents maximum signal; can be changed to dBm with the flag RADIO_LINK_STATS_FLAGS_RSSI_DBM.</description>
|
||||
<field type="uint8_t" name="flags" enum="RADIO_LINK_STATS_FLAGS" display="bitmask">Radio link statistics flags.</field>
|
||||
<field type="uint8_t" name="rx_LQ" units="c%" invalid="UINT8_MAX">Values: 0..100. UINT8_MAX: invalid/unknown.</field>
|
||||
<field type="uint8_t" name="rx_rssi1" invalid="UINT8_MAX">Rssi of antenna1. UINT8_MAX: invalid/unknown.</field>
|
||||
<field type="int8_t" name="rx_snr1" invalid="INT8_MAX">Noise on antenna1. Radio dependent. INT8_MAX: invalid/unknown.</field>
|
||||
<field type="uint8_t" name="rx_rssi2" invalid="UINT8_MAX">Rssi of antenna2. UINT8_MAX: ignore/unknown, use rx_rssi1.</field>
|
||||
<field type="int8_t" name="rx_snr2" invalid="INT8_MAX">Noise on antenna2. Radio dependent. INT8_MAX: ignore/unknown, use rx_snr1.</field>
|
||||
<field type="uint8_t" name="rx_receive_antenna" invalid="UINT8_MAX">0: antenna1, 1: antenna2, UINT8_MAX: ignore, no Rx receive diversity, use rx_rssi1, rx_snr1.</field>
|
||||
<field type="uint8_t" name="rx_transmit_antenna" invalid="UINT8_MAX">0: antenna1, 1: antenna2, UINT8_MAX: ignore, no Rx transmit diversity.</field>
|
||||
<field type="uint8_t" name="tx_LQ" units="c%" invalid="UINT8_MAX">Values: 0..100. UINT8_MAX: invalid/unknown.</field>
|
||||
<field type="uint8_t" name="tx_rssi1" invalid="UINT8_MAX">Rssi of antenna1. UINT8_MAX: invalid/unknown.</field>
|
||||
<field type="int8_t" name="tx_snr1" invalid="INT8_MAX">Noise on antenna1. Radio dependent. INT8_MAX: invalid/unknown.</field>
|
||||
<field type="uint8_t" name="tx_rssi2" invalid="UINT8_MAX">Rssi of antenna2. UINT8_MAX: ignore/unknown, use tx_rssi1.</field>
|
||||
<field type="int8_t" name="tx_snr2" invalid="INT8_MAX">Noise on antenna2. Radio dependent. INT8_MAX: ignore/unknown, use tx_snr1.</field>
|
||||
<field type="uint8_t" name="tx_receive_antenna" invalid="UINT8_MAX">0: antenna1, 1: antenna2, UINT8_MAX: ignore, no Tx receive diversity, use tx_rssi1, tx_snr1.</field>
|
||||
<field type="uint8_t" name="tx_transmit_antenna" invalid="UINT8_MAX">0: antenna1, 1: antenna2, UINT8_MAX: ignore, no Tx transmit diversity.</field>
|
||||
</message>
|
||||
<!-- ********** -->
|
||||
<message id="60040" name="FRSKY_PASSTHROUGH_ARRAY">
|
||||
<description>Frsky SPort passthrough multi packet container.</description>
|
||||
<field type="uint32_t" name="time_boot_ms" units="ms">Timestamp (time since system boot).</field>
|
||||
<field type="uint8_t" name="count">Number of passthrough packets in this message.</field>
|
||||
<field type="uint8_t[240]" name="packet_buf">Passthrough packet buffer. A packet has 6 bytes: uint16_t id + uint32_t data. The array has space for 40 packets.</field>
|
||||
</message>
|
||||
<!-- ********** -->
|
||||
<message id="60041" name="PARAM_VALUE_ARRAY">
|
||||
<description>Parameter multi param value container.</description>
|
||||
<field type="uint16_t" name="param_count">Total number of onboard parameters.</field>
|
||||
<field type="uint16_t" name="param_index_first">Index of the first onboard parameter in this array.</field>
|
||||
<field type="uint8_t" name="param_array_len">Number of onboard parameters in this array.</field>
|
||||
<field type="uint16_t" name="flags">Flags.</field>
|
||||
<field type="uint8_t[248]" name="packet_buf">Parameters buffer. Contains a series of variable length parameter blocks, one per parameter, with format as specifed elsewhere.</field>
|
||||
</message>
|
||||
<!-- ********** -->
|
||||
</messages>
|
||||
</mavlink>
|
||||
|
||||
@@ -2,7 +2,7 @@
|
||||
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||
<package format="3">
|
||||
<name>mavlink</name>
|
||||
<version>2022.12.30</version>
|
||||
<version>2023.5.5</version>
|
||||
<description>MAVLink message marshaling library.
|
||||
This package provides C-headers and C++11 library
|
||||
for both 1.0 and 2.0 versions of protocol.
|
||||
|
||||
17
pymavlink/.github/workflows/test.yml
vendored
17
pymavlink/.github/workflows/test.yml
vendored
@@ -15,9 +15,10 @@ jobs:
|
||||
python-version: ['2.7', '3.5', '3.6', '3.7', '3.8', '3.9', '3.10']
|
||||
|
||||
steps:
|
||||
- uses: actions/checkout@v2
|
||||
- uses: actions/checkout@v3
|
||||
- name: Set up Python ${{ matrix.python-version }}
|
||||
uses: actions/setup-python@v2
|
||||
|
||||
uses: actions/setup-python@v4
|
||||
with:
|
||||
python-version: ${{ matrix.python-version }}
|
||||
- name: Install dependencies
|
||||
@@ -31,10 +32,11 @@ jobs:
|
||||
if [ -f requirements.txt ]; then pip install -r requirements.txt; fi
|
||||
sudo apt update
|
||||
sudo apt install -y libgtest-dev g++
|
||||
- uses: actions/setup-node@v2-beta
|
||||
|
||||
- uses: actions/setup-node@v3
|
||||
with:
|
||||
node-version: '12'
|
||||
- run: npm install
|
||||
node-version: '16'
|
||||
|
||||
- name: Lint with flake8
|
||||
run: |
|
||||
# stop the build if there are Python syntax errors or undefined names
|
||||
@@ -67,6 +69,7 @@ jobs:
|
||||
flake8 --ignore='W503,E203,E501,E741' --statistics dialects/
|
||||
mypy --config-file ./.github/workflows/mypy-generated.ini dialects/v10/*.py dialects/v20/*.py
|
||||
fi
|
||||
|
||||
- name: Generate messages
|
||||
run: |
|
||||
mavgen.py --lang='C' --output=/tmp/mavgen_test mavlink/message_definitions/v1.0/common.xml --wire-protocol=1.0 --strict-units
|
||||
@@ -95,9 +98,9 @@ jobs:
|
||||
run: |
|
||||
./test_generator.sh
|
||||
|
||||
- name : Test NPM
|
||||
- name : Test JavaScript Bindings - generated tests and Mocha tests
|
||||
run: |
|
||||
cd generator/javascript && npm test
|
||||
./test_gen_js.sh && cd generator/javascript && npm test && cd -
|
||||
|
||||
- name: Test with pytest
|
||||
run: |
|
||||
|
||||
8
pymavlink/generator/Ada/examples/README
Normal file
8
pymavlink/generator/Ada/examples/README
Normal file
@@ -0,0 +1,8 @@
|
||||
Examples use Mavlink library.
|
||||
For build and run:
|
||||
|
||||
$ cd path/examples
|
||||
$ bash make.sh
|
||||
$ ./attitude
|
||||
$ ./param_request_list
|
||||
$ ./param_set_sr0_params
|
||||
57
pymavlink/generator/Ada/examples/attitude.adb
Normal file
57
pymavlink/generator/Ada/examples/attitude.adb
Normal file
@@ -0,0 +1,57 @@
|
||||
-- Connects to ardupilot (baud rate 115200) via ttyUSB0 and read all params
|
||||
-- Copyright Fil Andrii root.fi36@gmail.com 2022s
|
||||
|
||||
with Ada.Streams;
|
||||
with GNAT.Serial_Communications;
|
||||
with Ada.Text_IO;
|
||||
with Interfaces;
|
||||
with Ada.Numerics.Generic_Elementary_Functions;
|
||||
|
||||
with Mavlink;
|
||||
with Mavlink.Connection;
|
||||
with Mavlink.Messages;
|
||||
with Mavlink.Types;
|
||||
|
||||
procedure Attitude is
|
||||
use type Ada.Streams.Stream_Element_Offset;
|
||||
use type Interfaces.Unsigned_8;
|
||||
package Short_Float_Text_IO is new Ada.Text_IO.Float_IO(Short_Float);
|
||||
|
||||
Ser : GNAT.Serial_Communications.Serial_Port;
|
||||
Input : Ada.Streams.Stream_Element_Array(1..1024);
|
||||
Input_Last : Ada.Streams.Stream_Element_Offset;
|
||||
|
||||
Mav_Conn : Mavlink.Connection.Connection (System_Id => 250);
|
||||
|
||||
procedure Handler_Attitude is
|
||||
Attitude : Mavlink.Messages.Attitude;
|
||||
K_Rad2Deg : Short_Float := 180.0 / Ada.Numerics.Pi;
|
||||
begin
|
||||
Mav_Conn.Unpack (Attitude);
|
||||
|
||||
Ada.Text_IO.Put ("Pitch: ");
|
||||
Short_Float_Text_IO.Put(Attitude.Pitch * K_Rad2Deg, Aft => 4, Exp => 0);
|
||||
Ada.Text_IO.Put (" Roll: ");
|
||||
Short_Float_Text_IO.Put(Attitude.Roll * K_Rad2Deg, Aft => 4, Exp => 0);
|
||||
Ada.Text_IO.Put (" Yaw: ");
|
||||
Short_Float_Text_IO.Put(Attitude.Yaw * K_Rad2Deg, Aft => 4, Exp => 0);
|
||||
Ada.Text_IO.New_Line;
|
||||
end Handler_Attitude;
|
||||
|
||||
begin
|
||||
Ada.Text_IO.Put_Line ("Connects to ardupilot (baud rate 115200) via ttyUSB0 and reads attitude angles");
|
||||
|
||||
GNAT.Serial_Communications.Open (Port => Ser, Name => "/dev/ttyUSB0");
|
||||
GNAT.Serial_Communications.Set (Port => Ser, Rate => GNAT.Serial_Communications.B115200, Block => True, Timeout => 0.0);
|
||||
|
||||
loop
|
||||
GNAT.Serial_Communications.Read (Port => Ser, Buffer => Input, Last => Input_Last);
|
||||
for B of Input (Input'First .. Input_Last) loop
|
||||
if Mav_Conn.Parse_Byte(Interfaces.Unsigned_8(B)) then
|
||||
if Mav_Conn.Get_Msg_Id = Mavlink.Messages.Attitude_Id then
|
||||
Handler_Attitude;
|
||||
end if;
|
||||
end if;
|
||||
end loop;
|
||||
end loop;
|
||||
end Attitude;
|
||||
7
pymavlink/generator/Ada/examples/make.sh
Normal file
7
pymavlink/generator/Ada/examples/make.sh
Normal file
@@ -0,0 +1,7 @@
|
||||
#!/bin/bash
|
||||
|
||||
mkdir build
|
||||
|
||||
gnatmake -a --create-missing-dirs attitude.adb -D build -I..
|
||||
gnatmake -a --create-missing-dirs param_request_list.adb -D build -I..
|
||||
gnatmake -a --create-missing-dirs param_set_sr0_params -D build -I..
|
||||
67
pymavlink/generator/Ada/examples/param_request_list.adb
Normal file
67
pymavlink/generator/Ada/examples/param_request_list.adb
Normal file
@@ -0,0 +1,67 @@
|
||||
-- Connects to ardupilot (baud rate 115200) via ttyUSB0 and read all params
|
||||
-- Copyright Fil Andrii root.fi36@gmail.com 2022
|
||||
|
||||
with Ada.Streams;
|
||||
with GNAT.Serial_Communications;
|
||||
with Ada.Text_IO;
|
||||
with Interfaces;
|
||||
with Ada.Numerics.Generic_Elementary_Functions;
|
||||
with Ada.Strings;
|
||||
with Ada.Strings.Fixed;
|
||||
with Ada.Strings.Maps;
|
||||
|
||||
with Mavlink;
|
||||
with Mavlink.Connection;
|
||||
with Mavlink.Messages;
|
||||
with Mavlink.Types;
|
||||
|
||||
procedure Param_Request_List is
|
||||
use type Ada.Streams.Stream_Element_Offset;
|
||||
use type Interfaces.Unsigned_8;
|
||||
package Short_Float_Text_IO is new Ada.Text_IO.Float_IO(Short_Float);
|
||||
|
||||
Ser : GNAT.Serial_Communications.Serial_Port;
|
||||
Input : Ada.Streams.Stream_Element_Array(1..1024);
|
||||
Input_Last : Ada.Streams.Stream_Element_Offset;
|
||||
Output : Ada.Streams.Stream_Element_Array(1..1024);
|
||||
Output_Last : Ada.Streams.Stream_Element_Offset := Output'First;
|
||||
|
||||
Mav_Conn : Mavlink.Connection.Connection (System_Id => 250);
|
||||
|
||||
procedure Handler_Param_Value is
|
||||
Param_Value : Mavlink.Messages.Param_Value;
|
||||
begin
|
||||
Mav_Conn.Unpack (Param_Value);
|
||||
Ada.Text_IO.Put (Param_Value.Param_Id & " = ");
|
||||
Short_Float_Text_IO.Put (Param_Value.Param_Value, Aft => 4, Exp => 0);
|
||||
Ada.Text_IO.New_Line;
|
||||
end Handler_Param_Value;
|
||||
|
||||
Param_Request_List : Mavlink.Messages.Param_Request_List;
|
||||
|
||||
begin
|
||||
Ada.Text_IO.Put_Line ("Connects to ardupilot (baud rate 115200) via ttyUSB0 and read all params");
|
||||
|
||||
GNAT.Serial_Communications.Open (Port => Ser, Name => "/dev/ttyUSB0");
|
||||
GNAT.Serial_Communications.Set (Port => Ser, Rate => GNAT.Serial_Communications.B115200, Block => True, Timeout => 0.0);
|
||||
|
||||
Param_Request_List.Target_System := 1;
|
||||
Param_Request_List.Target_Component := 0;
|
||||
|
||||
for B of Mav_Conn.Pack (Param_Request_List) loop
|
||||
Output (Output_Last) := Ada.Streams.Stream_Element (B);
|
||||
Output_Last := Output_Last + 1;
|
||||
end loop;
|
||||
GNAT.Serial_Communications.Write (Port => Ser, Buffer => Output (Output'First .. Output_Last));
|
||||
|
||||
loop
|
||||
GNAT.Serial_Communications.Read (Port => Ser, Buffer => Input, Last => Input_Last);
|
||||
for B of Input (Input'First .. Input_Last) loop
|
||||
if Mav_Conn.Parse_Byte(Interfaces.Unsigned_8(B)) then
|
||||
if Mav_Conn.Get_Msg_Id = Mavlink.Messages.Param_Value_Id then
|
||||
Handler_Param_Value;
|
||||
end if;
|
||||
end if;
|
||||
end loop;
|
||||
end loop;
|
||||
end Param_Request_List;
|
||||
80
pymavlink/generator/Ada/examples/param_set_sr0_params.adb
Normal file
80
pymavlink/generator/Ada/examples/param_set_sr0_params.adb
Normal file
@@ -0,0 +1,80 @@
|
||||
-- Connects to ardupilot (baud rate 115200) via ttyUSB0 and set SR0_PARAMS to 11.
|
||||
-- Copyright Fil Andrii root.fi36@gmail.com 2022
|
||||
|
||||
with Ada.Streams;
|
||||
with GNAT.Serial_Communications;
|
||||
with Ada.Text_IO;
|
||||
with Interfaces;
|
||||
with Ada.Numerics.Generic_Elementary_Functions;
|
||||
with Ada.Strings;
|
||||
with Ada.Strings.Fixed;
|
||||
with Ada.Strings.Maps;
|
||||
|
||||
with Mavlink;
|
||||
with Mavlink.Connection;
|
||||
with Mavlink.Messages;
|
||||
with Mavlink.Types;
|
||||
|
||||
procedure Param_Set_SR0_PARAMS is
|
||||
use type Ada.Streams.Stream_Element_Offset;
|
||||
use type Interfaces.Unsigned_8;
|
||||
package Short_Float_Text_IO is new Ada.Text_IO.Float_IO(Short_Float);
|
||||
|
||||
Ser : GNAT.Serial_Communications.Serial_Port;
|
||||
Input : Ada.Streams.Stream_Element_Array(1..1024);
|
||||
Input_Last : Ada.Streams.Stream_Element_Offset;
|
||||
Output : Ada.Streams.Stream_Element_Array(1..1024);
|
||||
Output_Last : Ada.Streams.Stream_Element_Offset := Output'First;
|
||||
|
||||
Mav_Conn : Mavlink.Connection.Connection (System_Id => 250);
|
||||
|
||||
function Handler_Param_Value return Boolean is
|
||||
Param_Value : Mavlink.Messages.Param_Value;
|
||||
begin
|
||||
Mav_Conn.Unpack (Param_Value);
|
||||
if Ada.Strings.Fixed.Trim (Source => Param_Value.Param_Id,
|
||||
Left => Ada.Strings.Maps.Null_Set,
|
||||
Right => Ada.Strings.Maps.To_Set (ASCII.Nul)) = "SR0_PARAMS" then
|
||||
Ada.Text_IO.Put (Param_Value.Param_Id & " = ");
|
||||
Short_Float_Text_IO.Put (Param_Value.Param_Value, Aft => 4, Exp => 0);
|
||||
Ada.Text_IO.New_Line;
|
||||
|
||||
return True;
|
||||
end if;
|
||||
return False;
|
||||
end Handler_Param_Value;
|
||||
|
||||
Param_Set : Mavlink.Messages.Param_Set;
|
||||
|
||||
begin
|
||||
Ada.Text_IO.Put_Line ("Connects to ardupilot (baud rate 115200) via ttyUSB0 and set SR0_PARAMS to 11.");
|
||||
Ada.Text_IO.Put_Line ("Warning this app change param SR0_PARAMS to 11!");
|
||||
|
||||
GNAT.Serial_Communications.Open (Port => Ser, Name => "/dev/ttyUSB0");
|
||||
GNAT.Serial_Communications.Set (Port => Ser, Rate => GNAT.Serial_Communications.B115200, Block => True, Timeout => 0.0);
|
||||
|
||||
Param_Set.Target_System := 1;
|
||||
Param_Set.Target_Component := 0;
|
||||
Param_Set.Param_Id := Ada.Strings.Fixed.Head(Source => "SR0_PARAMS", Count => 16, Pad => ASCII.Nul);
|
||||
Param_Set.Param_Value := 11.0;
|
||||
Param_Set.Param_Type := Mavlink.Types.Mav_Param_Type_Real32;
|
||||
|
||||
for B of Mav_Conn.Pack (Param_Set) loop
|
||||
Output (Output_Last) := Ada.Streams.Stream_Element (B);
|
||||
Output_Last := Output_Last + 1;
|
||||
end loop;
|
||||
GNAT.Serial_Communications.Write (Port => Ser, Buffer => Output (Output'First .. Output_Last));
|
||||
|
||||
Main_Loop: loop
|
||||
GNAT.Serial_Communications.Read (Port => Ser, Buffer => Input, Last => Input_Last);
|
||||
for B of Input (Input'First .. Input_Last) loop
|
||||
if Mav_Conn.Parse_Byte(Interfaces.Unsigned_8(B)) then
|
||||
if Mav_Conn.Get_Msg_Id = Mavlink.Messages.Param_Value_Id then
|
||||
if Handler_Param_Value then
|
||||
exit Main_Loop;
|
||||
end if;
|
||||
end if;
|
||||
end if;
|
||||
end loop;
|
||||
end loop Main_Loop;
|
||||
end Param_Set_SR0_PARAMS;
|
||||
89
pymavlink/generator/Ada/mavlink-connection.adb
Normal file
89
pymavlink/generator/Ada/mavlink-connection.adb
Normal file
@@ -0,0 +1,89 @@
|
||||
-- Mavlink connection
|
||||
-- Copyright Fil Andrii root.fi36@gmail.com 2022
|
||||
|
||||
with Ada.Assertions;
|
||||
|
||||
package body Mavlink.Connection is
|
||||
|
||||
function Parse_Byte (Conn : in out Connection;
|
||||
Val : Interfaces.Unsigned_8) return Boolean is
|
||||
use type Interfaces.Unsigned_8;
|
||||
begin
|
||||
Conn.In_Buf (Conn.In_Ptr) := Val;
|
||||
|
||||
if Conn.In_Ptr = 0 then
|
||||
if Val /= Packet_Marker then
|
||||
return False;
|
||||
end if;
|
||||
X25CRC.Reset (Conn.Checksum);
|
||||
elsif Conn.In_Ptr = 1 then
|
||||
Conn.Len := Natural (Val) + Packet_Header_Length + Packet_Marker_Length;
|
||||
X25CRC.Reset (Conn.Checksum);
|
||||
X25CRC.Update (Conn.Checksum, Val);
|
||||
elsif Conn.In_Ptr > Conn.Len then
|
||||
X25CRC.Update (Conn.Checksum, Mavlink.Messages.CRC_Extras (Conn.In_Buf (Pos_Msg_id)));
|
||||
|
||||
Conn.In_Ptr := 0;
|
||||
return Conn.Checksum.High = Conn.In_Buf (Conn.Len) and Conn.Checksum.Low = Conn.In_Buf (Conn.Len + 1);
|
||||
elsif Conn.In_Ptr /= Conn.Len then
|
||||
X25CRC.Update (Conn.Checksum, Val);
|
||||
end if;
|
||||
|
||||
Conn.In_Ptr := Conn.In_Ptr + 1;
|
||||
return False;
|
||||
end Parse_Byte;
|
||||
|
||||
function Get_Msg_Id (Conn : Connection) return Msg_Id is
|
||||
begin
|
||||
return Conn.In_Buf (Pos_Msg_id);
|
||||
end Get_Msg_Id;
|
||||
|
||||
function Pack (Conn : in out Connection;
|
||||
Msg : Mavlink.Messages.Message'Class) return Byte_Arrray is
|
||||
use type Interfaces.Unsigned_8;
|
||||
|
||||
Buf : Byte_Arrray (0 .. Natural(Msg.Payload_Length) + Packet_Control_Info_Size - 1);
|
||||
Buf_Ptr : Natural;
|
||||
Checksum : X25CRC.Checksum;
|
||||
|
||||
Fake_array : Byte_Arrray (0 .. Msg'Size / 8 - 1)
|
||||
with Address => Msg'Address, Import => True, Convention => Ada;
|
||||
|
||||
begin
|
||||
|
||||
Buf (0 .. 5) := (Packet_Marker, Msg.Payload_Length, Conn.Out_Sequency,
|
||||
Conn.System_Id, Conn.Component_Id, Msg.Message_Id);
|
||||
Buf_Ptr := Natural (Msg.Payload_Length) + 5;
|
||||
Buf (6 .. Buf_Ptr) := Fake_array (Message_Size .. Message_Size + Natural (Msg.Payload_Length) - 1);
|
||||
|
||||
Conn.Out_Sequency := Conn.Out_Sequency + 1;
|
||||
|
||||
for B of Buf (1 .. Buf_Ptr) loop
|
||||
X25CRC.Update (Checksum, B);
|
||||
end loop;
|
||||
X25CRC.Update (Checksum, Messages.CRC_Extras (Msg.Message_Id));
|
||||
|
||||
Buf (Buf_Ptr + 1) := Checksum.High;
|
||||
Buf (Buf_Ptr + 2) := Checksum.Low;
|
||||
|
||||
return Buf;
|
||||
|
||||
end Pack;
|
||||
|
||||
procedure Unpack (Conn : in out Connection;
|
||||
Msg : in out Mavlink.Messages.Message'Class) is
|
||||
use type Interfaces.Unsigned_8;
|
||||
|
||||
Fake_array : Byte_Arrray (0 .. Msg'Size / 8 - 1)
|
||||
with Address => Msg'Address, Import => True, Convention => Ada;
|
||||
begin
|
||||
|
||||
Ada.Assertions.Assert (Msg.Payload_Length = Conn.In_Buf (1) and Msg.Message_Id = Conn.In_Buf (Pos_Msg_Id));
|
||||
|
||||
Fake_array (Tag_Length + 1 .. Tag_Length + 3) := Conn.In_Buf (2 .. 4);
|
||||
Fake_array (Message_Size .. Message_Size - 1 + Natural (Msg.Payload_Length)) :=
|
||||
Conn.In_Buf (Packet_Payload_First .. Packet_Payload_First - 1 + Natural (Msg.Payload_Length));
|
||||
|
||||
end Unpack;
|
||||
|
||||
end Mavlink.Connection;
|
||||
38
pymavlink/generator/Ada/mavlink-connection.ads
Normal file
38
pymavlink/generator/Ada/mavlink-connection.ads
Normal file
@@ -0,0 +1,38 @@
|
||||
-- Mavlink connection
|
||||
-- Copyright Fil Andrii root.fi36@gmail.com 2022
|
||||
|
||||
with Interfaces;
|
||||
with Mavlink.Messages;
|
||||
with X25CRC;
|
||||
|
||||
package Mavlink.Connection is
|
||||
|
||||
pragma Pure (Mavlink.Connection);
|
||||
|
||||
type Connection (System_Id : Interfaces.Unsigned_8) is tagged private;
|
||||
|
||||
function Parse_Byte (Conn : in out Connection; Val : Interfaces.Unsigned_8)
|
||||
return Boolean;
|
||||
|
||||
function Get_Msg_Id (Conn : Connection) return Msg_Id;
|
||||
|
||||
function Pack (Conn : in out Connection;
|
||||
Msg : Mavlink.Messages.Message'Class) return Byte_Arrray;
|
||||
|
||||
procedure Unpack (Conn : in out Connection;
|
||||
Msg : in out Mavlink.Messages.Message'Class);
|
||||
|
||||
private
|
||||
|
||||
Pos_Msg_Id : constant Natural := 5;
|
||||
|
||||
type Connection (System_Id : Interfaces.Unsigned_8) is tagged record
|
||||
Component_Id : Interfaces.Unsigned_8 := 1;
|
||||
In_Buf : Byte_Arrray (0 .. 255 + 8) := (others => 0);
|
||||
In_Ptr : Natural := 0;
|
||||
Len : Natural := 0;
|
||||
Out_Sequency : Interfaces.Unsigned_8 := 0;
|
||||
Checksum : X25CRC.Checksum;
|
||||
end record;
|
||||
|
||||
end Mavlink.Connection;
|
||||
49
pymavlink/generator/Ada/mavlink.ads
Normal file
49
pymavlink/generator/Ada/mavlink.ads
Normal file
@@ -0,0 +1,49 @@
|
||||
-- Mavlink
|
||||
-- Copyright Fil Andrii root.fi36@gmail.com 2022
|
||||
|
||||
with Interfaces;
|
||||
|
||||
package Mavlink is
|
||||
|
||||
pragma Pure (Mavlink);
|
||||
|
||||
Packet_Marker : constant Interfaces.Unsigned_8 := 16#FE#;
|
||||
Packet_Marker_Length : constant := 1;
|
||||
Packet_Checksum_Length : constant := 2;
|
||||
Packet_Header_Length : constant := 5;
|
||||
Packet_Payload_First : constant := Packet_Header_Length + Packet_Marker_Length;
|
||||
Packet_Control_INfo_Size : constant := Packet_Marker_Length + Packet_Header_Length + Packet_Checksum_Length;
|
||||
|
||||
Tag_Length : constant := Standard'Address_Size / 8;
|
||||
|
||||
Message_Alignment : constant := 8;
|
||||
Message_Size : constant := Positive (Float'Ceiling (Float (Tag_Length + Packet_Header_Length) /
|
||||
Float (Message_Alignment))) * Message_Alignment;
|
||||
|
||||
subtype Msg_Id is Interfaces.Unsigned_8;
|
||||
|
||||
type Byte_Arrray is array (Natural range <>) of Interfaces.Unsigned_8;
|
||||
|
||||
type Unsigned_8_Array is array (Natural range <>) of Interfaces.Unsigned_8
|
||||
with Component_Size => 8;
|
||||
type Unsigned_16_Array is array (Natural range <>) of Interfaces.Unsigned_16
|
||||
with Component_Size => 16;
|
||||
type Unsigned_32_Array is array (Natural range <>) of Interfaces.Unsigned_32
|
||||
with Component_Size => 32;
|
||||
type Unsigned_64_Array is array (Natural range <>) of Interfaces.Unsigned_64
|
||||
with Component_Size => 64;
|
||||
type Integer_8_Array is array (Natural range <>) of Interfaces.Integer_8
|
||||
with Component_Size => 8;
|
||||
type Integer_16_Array is array (Natural range <>) of Interfaces.Integer_16
|
||||
with Component_Size => 16;
|
||||
type Integer_32_Array is array (Natural range <>) of Interfaces.Integer_32
|
||||
with Component_Size => 32;
|
||||
type Integer_64_Array is array (Natural range <>) of Interfaces.Integer_64
|
||||
with Component_Size => 64;
|
||||
type Short_Float_Array is array (Natural range <>) of Short_Float
|
||||
with Component_Size => 32;
|
||||
type Long_Float_Array is array (Natural range <>) of Long_Float
|
||||
with Component_Size => 64;
|
||||
|
||||
end Mavlink;
|
||||
|
||||
23
pymavlink/generator/Ada/x25crc.adb
Normal file
23
pymavlink/generator/Ada/x25crc.adb
Normal file
@@ -0,0 +1,23 @@
|
||||
-- Package body for crc checksum
|
||||
-- Copyright Fil Andrii root.fi36@gmail.com 2022
|
||||
|
||||
package body X25CRC is
|
||||
|
||||
procedure Reset (Element : in out Checksum) is
|
||||
begin
|
||||
Element.Low := 16#FF#;
|
||||
Element.High := 16#FF#;
|
||||
end Reset;
|
||||
|
||||
procedure Update (Element : in out Checksum; Value : Unsigned_8) is
|
||||
use type Unsigned_16;
|
||||
|
||||
Tmp : Unsigned_16;
|
||||
begin
|
||||
Tmp := Unsigned_16 (Value) xor (Element.Value and 16#FF#);
|
||||
Tmp := (Tmp xor Shift_Left (Tmp, 4)) and 16#FF#;
|
||||
Element.Value :=
|
||||
Shift_Right (Element.Value, 8) xor Shift_Left (Tmp, 8) xor Shift_Left (Tmp, 3) xor Shift_Right (Tmp, 4);
|
||||
end Update;
|
||||
|
||||
end X25CRC;
|
||||
28
pymavlink/generator/Ada/x25crc.ads
Normal file
28
pymavlink/generator/Ada/x25crc.ads
Normal file
@@ -0,0 +1,28 @@
|
||||
-- Package for crc checksum
|
||||
-- Copyright Fil Andrii root.fi36@gmail.com 2022
|
||||
|
||||
with Interfaces; use Interfaces;
|
||||
|
||||
package X25CRC is
|
||||
|
||||
pragma Pure (X25CRC);
|
||||
|
||||
type Checksum (Repr : Boolean := True) is record
|
||||
case Repr is
|
||||
when True =>
|
||||
Low, High : Unsigned_8 := 16#FF#;
|
||||
when others =>
|
||||
Value : Unsigned_16 := 16#FFFF#;
|
||||
end case;
|
||||
end record with Size => 16, Unchecked_Union;
|
||||
for Checksum use record
|
||||
High at 0 range 0 .. 7;
|
||||
Low at 0 range 8 .. 15;
|
||||
|
||||
Value at 0 range 0 .. 15;
|
||||
end record;
|
||||
|
||||
procedure Reset (Element : in out Checksum);
|
||||
procedure Update (Element : in out Checksum; Value : Unsigned_8);
|
||||
|
||||
end X25CRC;
|
||||
@@ -248,8 +248,6 @@ MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg,
|
||||
#endif
|
||||
#endif
|
||||
|
||||
int bufferIndex = 0;
|
||||
|
||||
status->msg_received = MAVLINK_FRAMING_INCOMPLETE;
|
||||
|
||||
switch (status->parse_state)
|
||||
@@ -364,7 +362,6 @@ MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg,
|
||||
break;
|
||||
}
|
||||
|
||||
bufferIndex++;
|
||||
// If a message has been successfully decoded, check index
|
||||
if (status->msg_received == MAVLINK_FRAMING_OK)
|
||||
{
|
||||
|
||||
@@ -141,7 +141,8 @@ MAVLINK_HELPER bool mavlink_signature_check(mavlink_signing_t *signing,
|
||||
mavlink_sha256_update(&ctx, msg->ck, 2);
|
||||
mavlink_sha256_update(&ctx, psig, 1+6);
|
||||
mavlink_sha256_final_48(&ctx, signature);
|
||||
if (memcmp(signature, incoming_signature, 6) != 0) {
|
||||
if (memcmp(signature, incoming_signature, 6) != 0) {
|
||||
signing->last_status = MAVLINK_SIGNING_STATUS_BAD_SIGNATURE;
|
||||
return false;
|
||||
}
|
||||
|
||||
@@ -155,7 +156,8 @@ MAVLINK_HELPER bool mavlink_signature_check(mavlink_signing_t *signing,
|
||||
memcpy(tstamp.t8, psig+1, 6);
|
||||
|
||||
if (signing_streams == NULL) {
|
||||
return false;
|
||||
signing->last_status = MAVLINK_SIGNING_STATUS_NO_STREAMS;
|
||||
return false;
|
||||
}
|
||||
|
||||
// find stream
|
||||
@@ -169,11 +171,13 @@ MAVLINK_HELPER bool mavlink_signature_check(mavlink_signing_t *signing,
|
||||
if (i == signing_streams->num_signing_streams) {
|
||||
if (signing_streams->num_signing_streams >= MAVLINK_MAX_SIGNING_STREAMS) {
|
||||
// over max number of streams
|
||||
return false;
|
||||
signing->last_status = MAVLINK_SIGNING_STATUS_TOO_MANY_STREAMS;
|
||||
return false;
|
||||
}
|
||||
// new stream. Only accept if timestamp is not more than 1 minute old
|
||||
if (tstamp.t64 + 6000*1000UL < signing->timestamp) {
|
||||
return false;
|
||||
signing->last_status = MAVLINK_SIGNING_STATUS_OLD_TIMESTAMP;
|
||||
return false;
|
||||
}
|
||||
// add new stream
|
||||
signing_streams->stream[i].sysid = msg->sysid;
|
||||
@@ -186,7 +190,8 @@ MAVLINK_HELPER bool mavlink_signature_check(mavlink_signing_t *signing,
|
||||
memcpy(last_tstamp.t8, signing_streams->stream[i].timestamp_bytes, 6);
|
||||
if (tstamp.t64 <= last_tstamp.t64) {
|
||||
// repeating old timestamp
|
||||
return false;
|
||||
signing->last_status = MAVLINK_SIGNING_STATUS_REPLAY;
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -197,7 +202,8 @@ MAVLINK_HELPER bool mavlink_signature_check(mavlink_signing_t *signing,
|
||||
if (tstamp.t64 > signing->timestamp) {
|
||||
signing->timestamp = tstamp.t64;
|
||||
}
|
||||
return true;
|
||||
signing->last_status = MAVLINK_SIGNING_STATUS_OK;
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
@@ -585,7 +591,6 @@ MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg,
|
||||
mavlink_message_t* r_message,
|
||||
mavlink_status_t* r_mavlink_status)
|
||||
{
|
||||
int bufferIndex = 0;
|
||||
|
||||
status->msg_received = MAVLINK_FRAMING_INCOMPLETE;
|
||||
|
||||
@@ -816,7 +821,6 @@ MAVLINK_HELPER uint8_t mavlink_frame_char_buffer(mavlink_message_t* rxmsg,
|
||||
break;
|
||||
}
|
||||
|
||||
bufferIndex++;
|
||||
// If a message has been successfully decoded, check index
|
||||
if (status->msg_received == MAVLINK_FRAMING_OK)
|
||||
{
|
||||
|
||||
@@ -242,6 +242,16 @@ typedef bool (*mavlink_accept_unsigned_t)(const mavlink_status_t *status, uint32
|
||||
*/
|
||||
#define MAVLINK_SIGNING_FLAG_SIGN_OUTGOING 1 ///< Enable outgoing signing
|
||||
|
||||
typedef enum {
|
||||
MAVLINK_SIGNING_STATUS_NONE=0,
|
||||
MAVLINK_SIGNING_STATUS_OK=1,
|
||||
MAVLINK_SIGNING_STATUS_BAD_SIGNATURE=2,
|
||||
MAVLINK_SIGNING_STATUS_NO_STREAMS=3,
|
||||
MAVLINK_SIGNING_STATUS_TOO_MANY_STREAMS=4,
|
||||
MAVLINK_SIGNING_STATUS_OLD_TIMESTAMP=5,
|
||||
MAVLINK_SIGNING_STATUS_REPLAY=6,
|
||||
} mavlink_signing_status_t;
|
||||
|
||||
/*
|
||||
state of MAVLink signing for this channel
|
||||
*/
|
||||
@@ -251,6 +261,7 @@ typedef struct __mavlink_signing {
|
||||
uint64_t timestamp; ///< Timestamp, in microseconds since UNIX epoch GMT
|
||||
uint8_t secret_key[32];
|
||||
mavlink_accept_unsigned_t accept_unsigned_callback;
|
||||
mavlink_signing_status_t last_status;
|
||||
} mavlink_signing_t;
|
||||
|
||||
/*
|
||||
|
||||
@@ -56,7 +56,7 @@
|
||||
<PrivateAssets>all</PrivateAssets>
|
||||
<IncludeAssets>runtime; build; native; contentfiles; analyzers; buildtransitive</IncludeAssets>
|
||||
</PackageReference>
|
||||
<PackageReference Include="Newtonsoft.Json" Version="11.0.1" />
|
||||
<PackageReference Include="Newtonsoft.Json" Version="13.0.2" />
|
||||
</ItemGroup>
|
||||
|
||||
|
||||
|
||||
10522
pymavlink/generator/javascript/package-lock.json
generated
10522
pymavlink/generator/javascript/package-lock.json
generated
File diff suppressed because it is too large
Load Diff
@@ -8,7 +8,7 @@
|
||||
"glob": "^7.1.6",
|
||||
"jspack": "file:local_modules/jspack",
|
||||
"long": "file:local_modules/long",
|
||||
"mocha": "^8.2.0",
|
||||
"mocha": "^10.2.0",
|
||||
"should": "^13.2.3",
|
||||
"underscore": "1.12.1",
|
||||
"winston": "3.2.1"
|
||||
@@ -22,7 +22,7 @@
|
||||
"scripts": {
|
||||
"preinstall": "rm -rf implementations",
|
||||
"install": "cd .. && ./gen_js.sh",
|
||||
"pretest": "cd ../.. && ./test_gen_js.sh && npm install",
|
||||
"XpretestX": "cd ../.. && ./test_gen_js.sh",
|
||||
"test": "cd test ; python3 make_tests.py > made_tests.js ; cd .. ; mocha test",
|
||||
"lint": "./node_modules/.bin/eslint ./implementations/mavlink_common_v1.0/mavlink.js ./implementations/mavlink_common_v2.0/mavlink.js"
|
||||
}
|
||||
|
||||
@@ -45,7 +45,7 @@ MAXIMUM_INCLUDE_FILE_NESTING = 5
|
||||
|
||||
# List the supported languages. This is done globally because it's used by the GUI wrapper too
|
||||
# Right now, 'JavaScript' ~= 'JavaScript_Stable', in the future it may be made equivalent to 'JavaScript_NextGen'
|
||||
supportedLanguages = ["C", "CS", "JavaScript", "JavaScript_Stable","JavaScript_NextGen", "TypeScript", "Python2", "Python3", "Python", "Lua", "WLua", "ObjC", "Swift", "Java", "C++11"]
|
||||
supportedLanguages = ["Ada", "C", "CS", "JavaScript", "JavaScript_Stable","JavaScript_NextGen", "TypeScript", "Python2", "Python3", "Python", "Lua", "WLua", "ObjC", "Swift", "Java", "C++11"]
|
||||
|
||||
|
||||
def mavgen(opts, args):
|
||||
@@ -291,6 +291,12 @@ def mavgen(opts, args):
|
||||
elif opts.language == 'c++11':
|
||||
from . import mavgen_cpp11
|
||||
mavgen_cpp11.generate(opts.output, xml)
|
||||
elif opts.language == 'ada':
|
||||
if opts.wire_protocol != mavparse.PROTOCOL_1_0:
|
||||
raise DeprecationWarning("Error! Mavgen_Ada only supports protocol version 1.0")
|
||||
else:
|
||||
from . import mavgen_ada
|
||||
mavgen_ada.generate(opts.output, xml)
|
||||
else:
|
||||
print("Unsupported language %s" % opts.language)
|
||||
|
||||
|
||||
315
pymavlink/generator/mavgen_ada.py
Normal file
315
pymavlink/generator/mavgen_ada.py
Normal file
@@ -0,0 +1,315 @@
|
||||
#!/usr/bin/env python
|
||||
'''
|
||||
parse a MAVLink protocol XML file and generate a python implementation
|
||||
|
||||
Copyright Andrii Fil root.fi36@gmail.com 2022
|
||||
Based on mavgen_python.py
|
||||
Released under GNU GPL version 3 or later
|
||||
'''
|
||||
from __future__ import print_function
|
||||
|
||||
import os
|
||||
import math
|
||||
import shutil
|
||||
from operator import attrgetter
|
||||
from . import mavparse
|
||||
|
||||
reserved_words = (
|
||||
'abort', 'else', 'new', 'return', 'abs', 'elsif', 'not', 'reverse', 'abstract', 'end', 'null',
|
||||
'accept', 'entry', 'select', 'access', 'exception', 'of', 'separate', 'aliased', 'exit', 'or',
|
||||
'subtype', 'all', 'others', 'synchronized', 'and', 'for', 'out', 'array', 'function', 'overriding',
|
||||
'tagged', 'at', 'task', 'generic', 'package', 'terminate', 'begin', 'goto', 'pragma', 'then',
|
||||
'body', 'private', 'type', 'if', 'procedure', 'case', 'in', 'protected', 'until', 'constant',
|
||||
'interface', 'use', 'is', 'raise', 'declare', 'range', 'when', 'delay', 'limited', 'record',
|
||||
'while', 'delta', 'loop', 'rem', 'with', 'digits', 'renames', 'do', 'mod', 'requeue', 'xor')
|
||||
|
||||
reserved_fields = ('sequence', 'system_id', 'component_id', 'message_id')
|
||||
|
||||
# mavlink developers cannot understand that there are not only c-like languages :(
|
||||
try:
|
||||
math.log2(2)
|
||||
|
||||
def is_position(val):
|
||||
return math.log2(val).is_integer()
|
||||
except:
|
||||
def is_position(val):
|
||||
return 2 ** int(math.log(val, 2)) == val
|
||||
|
||||
def normalize_name(name, suffix):
|
||||
if name.lower() in reserved_words:
|
||||
return name + "_" + suffix
|
||||
return name
|
||||
|
||||
def normalize_field_name(name):
|
||||
n = normalize_name(name, "Field")
|
||||
if n.lower() in reserved_fields:
|
||||
return n + "_Field"
|
||||
return n
|
||||
|
||||
def normalize_message_name(name):
|
||||
return normalize_name(name, "Message")
|
||||
|
||||
def normalize_enum_name(name):
|
||||
return normalize_name(name, "Enum")
|
||||
|
||||
def normalize_entry_name(name):
|
||||
return normalize_name(name, "Entry")
|
||||
|
||||
field_types = {
|
||||
'uint8_t' : 'Interfaces.Unsigned_8',
|
||||
'uint16_t' : 'Interfaces.Unsigned_16',
|
||||
'uint32_t' : 'Interfaces.Unsigned_32',
|
||||
'uint64_t' : 'Interfaces.Unsigned_64',
|
||||
'int8_t' : 'Interfaces.Integer_8',
|
||||
'int16_t' : 'Interfaces.Integer_16',
|
||||
'int32_t' : 'Interfaces.Integer_32',
|
||||
'int64_t' : 'Interfaces.Integer_64',
|
||||
'float' : 'Short_Float',
|
||||
'double' : 'Long_Float'}
|
||||
|
||||
field_array_types = {
|
||||
'uint8_t' : 'Unsigned_8_Array',
|
||||
'uint16_t' : 'Unsigned_16_Array',
|
||||
'uint32_t' : 'Unsigned_32_Array',
|
||||
'uint64_t' : 'Unsigned_64_Array',
|
||||
'int8_t' : 'Integer_8_Array',
|
||||
'int16_t' : 'Integer_16_Array',
|
||||
'int32_t' : 'Integer_32_Array',
|
||||
'int64_t' : 'Integer_64_Array',
|
||||
'float' : 'Short_Float_Array',
|
||||
'double' : 'Long_Float_Array'}
|
||||
|
||||
def generate_mavlink_messages(outf, msgs):
|
||||
outf.write("""-- Defines Mavlink messages
|
||||
-- Copyright Fil Andrii root.fi36@gmail.com 2022
|
||||
|
||||
with Interfaces;
|
||||
with Mavlink.Types; use Mavlink.Types;
|
||||
|
||||
package Mavlink.Messages is
|
||||
|
||||
pragma Pure (Mavlink.Messages);
|
||||
|
||||
type Message
|
||||
(Message_Id : Msg_Id;
|
||||
Payload_Length : Interfaces.Unsigned_8) is abstract tagged record
|
||||
Sequence : Interfaces.Unsigned_8;
|
||||
System_Id : Interfaces.Unsigned_8;
|
||||
Component_Id : Interfaces.Unsigned_8;
|
||||
end record with Alignment => Message_Alignment, Size => Message_Size * 8;
|
||||
for Message use record
|
||||
Payload_Length at Tag_Length + 0 range 0 .. 7;
|
||||
Sequence at Tag_Length + 1 range 0 .. 7;
|
||||
System_Id at Tag_Length + 2 range 0 .. 7;
|
||||
Component_Id at Tag_Length + 3 range 0 .. 7;
|
||||
Message_Id at Tag_Length + 4 range 0 .. 7;
|
||||
end record;\n\n""")
|
||||
|
||||
max_len = 0
|
||||
for m in msgs:
|
||||
name_len = len(normalize_message_name(m.name))
|
||||
if name_len > max_len:
|
||||
max_len = name_len
|
||||
max_len += 3
|
||||
|
||||
s = ""
|
||||
for m in msgs:
|
||||
name = normalize_message_name(m.name).title()
|
||||
s += " %s : constant Msg_Id := %i;\n" % ((name + "_Id").ljust(max_len), m.id)
|
||||
outf.write(s)
|
||||
outf.write("\n")
|
||||
|
||||
s = ""
|
||||
for m in msgs:
|
||||
message_name = normalize_message_name(m.name).title()
|
||||
max_len = 0
|
||||
payload_length = 0
|
||||
for field in m.fields:
|
||||
payload_length += (field.array_length or 1) * field.type_length
|
||||
field_name_len = len(normalize_field_name(field.name))
|
||||
if field_name_len > max_len:
|
||||
max_len = field_name_len
|
||||
s += " type %s is new Message\n" % message_name
|
||||
s += " (Message_Id => %s_Id,\n Payload_Length => %i) with record\n" % (message_name, payload_length)
|
||||
for field in m.fields:
|
||||
field_name = normalize_field_name(field.name).title()
|
||||
s += " %s : " % field_name.ljust(max_len)
|
||||
if field.type == 'char':
|
||||
s += "String (1..%i)" % field.array_length
|
||||
else:
|
||||
if field.array_length:
|
||||
s += "%s (1..%i)" % (field_array_types[field.type], field.array_length)
|
||||
elif field.enum:
|
||||
s += "Types." + normalize_enum_name(field.enum).title()
|
||||
else:
|
||||
s += field_types[field.type]
|
||||
s += ";\n"
|
||||
s += " end record;\n"
|
||||
|
||||
offset = 0
|
||||
s += " for %s use record\n" % message_name
|
||||
for field in m.ordered_fields:
|
||||
field_name = normalize_field_name(field.name).title()
|
||||
field_size = (field.array_length or 1) * field.type_length * 8
|
||||
s += " %s at Message_Size + %i range 0 .. %i;\n" % (field_name.ljust(max_len), offset, field_size - 1)
|
||||
offset += field_size / 8
|
||||
s += " end record;\n\n"
|
||||
outf.write(s)
|
||||
|
||||
s = """ CRC_Extras : constant array (Interfaces.Unsigned_8'Range) of
|
||||
Interfaces.Unsigned_8 := \n (""";
|
||||
|
||||
item_len = 0
|
||||
l = 6
|
||||
for m in msgs:
|
||||
item = "%s => %s," % (str(m.id).ljust(3), str(m.crc_extra))
|
||||
item = item.ljust(12)
|
||||
item_len = len(item)
|
||||
if l + item_len > 79:
|
||||
s += "\n "
|
||||
l = 6
|
||||
l += item_len
|
||||
s += item
|
||||
s += "\n others => 0) with Size => 2048;\n"
|
||||
outf.write(s)
|
||||
|
||||
outf.write("\nend MAVLink.Messages;")
|
||||
|
||||
def repr_bitmask(enum, size):
|
||||
enum_name = normalize_enum_name(enum.name).title()
|
||||
s = " type %s is record\n" % enum_name
|
||||
|
||||
max_len = 0
|
||||
for i in enum.entry:
|
||||
if i.end_marker:
|
||||
break
|
||||
elif i.value == 0 or not is_position(i.value):
|
||||
continue
|
||||
name_len = len(normalize_entry_name(i.name))
|
||||
if name_len > max_len:
|
||||
max_len = name_len
|
||||
|
||||
for i in enum.entry:
|
||||
if i.end_marker:
|
||||
break
|
||||
elif i.value == 0:
|
||||
continue
|
||||
elif not is_position(i.value):
|
||||
print("%s ignored because the composite value!" % i.name)
|
||||
continue
|
||||
name = normalize_entry_name(i.name).title()
|
||||
s += " %s : Boolean := False;\n" % name.ljust(max_len)
|
||||
|
||||
s += " end record with Size => %i;\n" % (size * 8)
|
||||
|
||||
s += " for %s use record\n" % enum_name
|
||||
for i in enum.entry:
|
||||
if i.end_marker:
|
||||
break
|
||||
elif i.value == 0 or not is_position(i.value):
|
||||
continue
|
||||
name = normalize_entry_name(i.name).title()
|
||||
pos = int(math.log(i.value, 2))
|
||||
s += " %s at 0 range %i .. %i;\n" % (name.ljust(max_len), pos, pos)
|
||||
s += " end record;\n"
|
||||
|
||||
return s
|
||||
|
||||
def repr_enum(enum, size):
|
||||
enum_name = normalize_enum_name(enum.name).title()
|
||||
s = " type %s is\n (" % enum_name
|
||||
l = 6
|
||||
max_len = 0
|
||||
for i in enum.entry:
|
||||
if i.end_marker:
|
||||
break
|
||||
if max_len > 0:
|
||||
s += ", "
|
||||
l += 2
|
||||
|
||||
name = normalize_entry_name(i.name).title()
|
||||
name_len = len(name)
|
||||
if name_len > max_len:
|
||||
max_len = name_len
|
||||
l += name_len + 1
|
||||
if l > 80:
|
||||
l = name_len + 6
|
||||
s += "\n "
|
||||
s += "%s" % name
|
||||
|
||||
s += ")"
|
||||
aspect = " with Size => %i;\n" % (size * 8)
|
||||
if l + len(aspect) > 79:
|
||||
s += "\n "
|
||||
s += aspect;
|
||||
|
||||
s += " for %s use\n (" % enum_name
|
||||
l = 0
|
||||
for i in enum.entry:
|
||||
if i.end_marker:
|
||||
break
|
||||
if l > 0:
|
||||
s += ",\n "
|
||||
else:
|
||||
l = 1
|
||||
s += "%s => %i" % (normalize_entry_name(i.name).title().ljust(max_len), i.value)
|
||||
|
||||
s += ");\n"
|
||||
|
||||
return s
|
||||
|
||||
def generate_mavlink_types(outf, types, types_size):
|
||||
outf.write("""-- Defines Mavlink types
|
||||
-- Copyright Fil Andrii root.fi36@gmail.com 2022
|
||||
|
||||
package MAVLink.Types is
|
||||
|
||||
pragma Pure (Mavlink.Types);\n\n""")
|
||||
|
||||
for t in types:
|
||||
size = types_size[t.name]
|
||||
if size is not None:
|
||||
if t.bitmask:
|
||||
outf.write(repr_bitmask(t, size))
|
||||
else:
|
||||
outf.write(repr_enum(t, size))
|
||||
outf.write("\n")
|
||||
outf.write("end MAVLink.Types;")
|
||||
|
||||
def generate(directory, xml):
|
||||
'''generate complete Ada implementation'''
|
||||
mavparse.mkdir_p(directory)
|
||||
|
||||
msgs = []
|
||||
types = []
|
||||
filelist = []
|
||||
for x in xml:
|
||||
msgs.extend(x.message)
|
||||
types.extend(x.enum)
|
||||
filelist.append(os.path.basename(x.filename))
|
||||
msgs.sort(key=attrgetter('id'))
|
||||
|
||||
types_size = {t.name: None for t in types}
|
||||
for m in msgs:
|
||||
for f in m.fields:
|
||||
if f.enum:
|
||||
if types_size[f.enum] is None:
|
||||
types_size[f.enum] = f.type_length
|
||||
else:
|
||||
assert types_size[f.enum] == f.type_length, "Different size for one enum"
|
||||
|
||||
basepath = os.path.dirname(os.path.realpath(__file__))
|
||||
srcpath = os.path.join(basepath, 'Ada')
|
||||
shutil.copy(os.path.join(srcpath, "x25crc.ads"), directory)
|
||||
shutil.copy(os.path.join(srcpath, "x25crc.adb"), directory)
|
||||
shutil.copy(os.path.join(srcpath, "mavlink.ads"), directory)
|
||||
shutil.copy(os.path.join(srcpath, "mavlink-connection.ads"), directory)
|
||||
shutil.copy(os.path.join(srcpath, "mavlink-connection.adb"), directory)
|
||||
shutil.copytree(os.path.join(srcpath, "examples"), os.path.join(directory, "examples"), dirs_exist_ok=True)
|
||||
|
||||
print("Generate MAVLink.Types")
|
||||
with open(os.path.join(directory, "mavlink-types.ads"), "w") as f:
|
||||
generate_mavlink_types(f, types, types_size)
|
||||
print("Generate MAVLink.Messages")
|
||||
with open(os.path.join(directory, "mavlink-messages.ads"), "w") as f:
|
||||
generate_mavlink_messages(f, msgs)
|
||||
@@ -1226,69 +1226,69 @@ SAMPLING_MIN_LON = -180.0
|
||||
SAMPLING_MAX_LON = 180.0
|
||||
|
||||
declination_table = [
|
||||
[149.10950,139.10950,129.10950,119.10950,109.10949,99.10950,89.10950,79.10950,69.10950,59.10950,49.10950,39.10950,29.10950,19.10950,9.10950,-0.89050,-10.89050,-20.89050,-30.89050,-40.89050,-50.89050,-60.89050,-70.89050,-80.89050,-90.89050,-100.89050,-110.89050,-120.89050,-130.89050,-140.89050,-150.89050,-160.89050,-170.89050,179.10950,169.10950,159.10950,149.10950],
|
||||
[129.37759,117.14583,106.01898,95.84726,86.44522,77.63150,69.24826,61.16874,53.29825,45.57105,37.94414,30.38880,22.88112,15.39339,7.88854,0.31945,-7.36677,-15.22089,-23.28322,-31.57827,-40.11442,-48.88906,-57.89765,-67.14429,-76.65158,-86.46832,-96.67422,-107.38079,-118.72599,-130.85732,-143.89431,-157.86353,-172.61739,172.21319,157.16190,142.76170,129.37759],
|
||||
[85.60184,77.69003,71.32207,65.86993,60.92414,56.17033,51.35320,46.28164,40.84704,35.03587,28.92623,22.66416,16.41848,10.31921,4.39763,-1.44271,-7.40082,-13.70324,-20.51470,-27.87783,-35.70713,-43.83304,-52.06997,-60.27655,-68.39086,-76.44339,-84.56374,-93.00460,-102.21930,-113.07088,-127.37057,-149.05145,176.63172,138.21637,112.07842,96.22737,85.60184],
|
||||
[47.72047,46.41844,44.94283,43.50977,42.16271,40.77290,39.04552,36.59993,33.11430,28.45556,22.74662,16.37046,9.89648,3.90131,-1.27904,-5.73319,-9.95573,-14.61164,-20.21833,-26.91079,-34.40272,-42.16094,-49.65783,-56.52405,-62.55849,-67.66009,-71.72876,-74.52850,-75.43728,-72.72706,-60.57997,-20.41341,26.63644,42.82781,47.52694,48.39676,47.72047],
|
||||
[31.02920,31.23624,30.96588,30.54974,30.22312,30.09074,29.97250,29.32817,27.43015,23.68926,17.94459,10.65044,2.87620,-4.06486,-9.27368,-12.71750,-15.14455,-17.66990,-21.38496,-26.87077,-33.73354,-40.89381,-47.34608,-52.47467,-55.91656,-57.36320,-56.37027,-52.13926,-43.55753,-30.12705,-13.67554,1.91730,13.93567,22.07926,27.11546,29.86289,31.02920],
|
||||
[22.39580,22.91483,22.98471,22.79294,22.51132,22.37364,22.48467,22.51169,21.58462,18.60470,12.86231,4.67251,-4.38742,-12.20529,-17.49574,-20.37578,-21.69620,-22.20533,-22.93466,-25.58202,-30.65181,-36.60256,-41.68581,-44.89480,-45.67065,-43.68591,-38.75262,-30.86937,-20.99711,-11.25673,-2.98341,3.98182,9.94668,14.86513,18.60975,21.08265,22.39580],
|
||||
[16.86268,17.34487,17.55107,17.53468,17.27224,16.88812,16.63481,16.50963,15.80216,13.15648,7.42999,-1.11751,-10.42072,-17.95472,-22.58300,-24.81140,-25.51932,-24.64114,-22.09731,-20.12401,-21.49578,-25.56754,-29.71013,-31.93909,-31.38680,-28.14427,-22.75379,-15.84114,-8.81817,-3.40017,0.41409,3.84742,7.42617,10.85398,13.75385,15.78065,16.86268],
|
||||
[13.19097,13.44856,13.58422,13.65261,13.48939,13.02568,12.52149,12.14860,11.29753,8.56495,2.76096,-5.61344,-14.17225,-20.58114,-24.03412,-24.98709,-24.11858,-21.26636,-16.32028,-11.21874,-9.02165,-10.74849,-14.47798,-17.30779,-17.65042,-15.69359,-12.14311,-7.48791,-2.96526,-0.12587,1.36049,3.09789,5.60507,8.31685,10.73216,12.41267,13.19097],
|
||||
[10.92623,10.90181,10.82333,10.86460,10.78695,10.37670,9.88910,9.46007,8.36291,5.29505,-0.57591,-8.37062,-15.75003,-20.80957,-22.79710,-21.87616,-18.84351,-14.45358,-9.42840,-4.80202,-1.83473,-1.74130,-4.26028,-7.17479,-8.52577,-8.09283,-6.32284,-3.48771,-0.62426,0.78982,1.09893,2.05326,4.13896,6.57935,8.80977,10.35435,10.92623],
|
||||
[9.71011,9.51881,9.24068,9.25106,9.26720,8.95743,8.53646,8.00522,6.50726,2.98362,-2.85308,-9.84907,-15.97767,-19.64088,-20.07848,-17.56993,-13.32746,-8.73278,-4.74905,-1.53742,0.92858,1.76616,0.36916,-1.99224,-3.56114,-3.89436,-3.25158,-1.74963,-0.12369,0.39195,0.09209,0.65986,2.57335,5.00216,7.34943,9.08114,9.71011],
|
||||
[9.00312,9.03132,8.80862,8.92740,9.13380,8.96714,8.45876,7.49648,5.31405,1.20550,-4.60853,-10.79680,-15.64160,-17.86099,-17.02957,-13.81388,-9.48335,-5.27860,-2.08821,0.18491,2.08754,3.09405,2.33958,0.49969,-0.94208,-1.51458,-1.49063,-0.97753,-0.41673,-0.66423,-1.43031,-1.23789,0.43821,2.92085,5.61318,7.88479,9.00312],
|
||||
[8.03874,8.87718,9.23144,9.74451,10.27560,10.29756,9.57016,7.89237,4.74571,-0.17093,-6.17240,-11.69433,-15.25467,-16.11759,-14.45574,-11.15430,-7.17811,-3.38526,-0.55632,1.30997,2.82221,3.77763,3.40183,2.00714,0.77788,0.16424,-0.15468,-0.39946,-0.85273,-1.96753,-3.33820,-3.67623,-2.39633,0.05772,3.10388,6.04655,8.03874],
|
||||
[6.42021,8.49313,9.96485,11.21264,12.15378,12.34411,11.39654,9.00192,4.80210,-1.14083,-7.63429,-12.77860,-15.31639,-15.15258,-12.98558,-9.72317,-6.02652,-2.46224,0.32036,2.16718,3.52576,4.45316,4.47022,3.64413,2.71916,2.05267,1.37415,0.37187,-1.18524,-3.37771,-5.55055,-6.50029,-5.64204,-3.28034,-0.00971,3.47278,6.42021],
|
||||
[4.55870,7.84457,10.59505,12.78315,14.21311,14.53879,13.38981,10.37263,5.13228,-2.00167,-9.27410,-14.41195,-16.39580,-15.63899,-13.13217,-9.75841,-6.05603,-2.45211,0.55836,2.75052,4.36042,5.58048,6.24404,6.24213,5.76940,4.95204,3.62521,1.54168,-1.40447,-4.90584,-7.98277,-9.46456,-8.87577,-6.53558,-3.08458,0.80580,4.55870],
|
||||
[3.13967,7.31097,11.07216,14.15725,16.20221,16.79070,15.47250,11.72257,5.14656,-3.57391,-11.94254,-17.34882,-19.11810,-18.05435,-15.26042,-11.58179,-7.54393,-3.53438,0.07849,3.08157,5.54519,7.63184,9.31427,10.36791,10.53101,9.56965,7.27456,3.54700,-1.35789,-6.53724,-10.58593,-12.40763,-11.80293,-9.26734,-5.52522,-1.23338,3.13967],
|
||||
[2.40982,7.18541,11.61646,15.39834,18.09395,19.11444,17.67695,12.80844,3.91551,-7.49296,-17.41503,-23.01926,-24.41774,-22.89374,-19.60750,-15.34185,-10.59502,-5.72094,-1.00157,3.37937,7.37061,10.97982,14.11553,16.47981,17.57833,16.80075,13.55567,7.60935,-0.25054,-7.92815,-13.21489,-15.22877,-14.33921,-11.39247,-7.22465,-2.48217,2.40982],
|
||||
[1.84909,7.14349,12.09954,16.39700,19.54576,20.73345,18.58921,11.09809,-2.76476,-18.58691,-29.30539,-33.52891,-33.25409,-30.30365,-25.79412,-20.37504,-14.44263,-8.26365,-2.03561,4.09039,9.99389,15.55055,20.57404,24.74657,27.54152,28.12085,25.24078,17.56424,5.48335,-6.76322,-14.61951,-17.38523,-16.44524,-13.21307,-8.68808,-3.52579,1.84909],
|
||||
[-0.07018,5.11056,9.81033,13.43064,14.95811,12.44881,2.42652,-17.21607,-37.22275,-47.59912,-50.02338,-48.04885,-43.68750,-37.95581,-31.39385,-24.31250,-16.90710,-9.31264,-1.63265,6.04381,13.62973,21.02738,28.11104,34.69910,40.50309,45.02417,47.32932,45.58173,36.48238,17.86736,-1.80184,-12.43534,-15.24263,-13.75101,-10.05982,-5.28238,-0.07018],
|
||||
[-177.79784,-167.79784,-157.79784,-147.79784,-137.79784,-127.79784,-117.79784,-107.79784,-97.79784,-87.79784,-77.79784,-67.79784,-57.79784,-47.79784,-37.79784,-27.79784,-17.79784,-7.79784,2.20217,12.20217,22.20217,32.20217,42.20217,52.20217,62.20217,72.20217,82.20217,92.20217,102.20217,112.20217,122.20217,132.20217,142.20217,152.20217,162.20217,172.20217,-177.79784]
|
||||
[148.83402,138.83401,128.83401,118.83402,108.83402,98.83402,88.83402,78.83402,68.83402,58.83402,48.83402,38.83402,28.83402,18.83402,8.83402,-1.16598,-11.16598,-21.16598,-31.16598,-41.16598,-51.16598,-61.16598,-71.16598,-81.16598,-91.16598,-101.16598,-111.16598,-121.16598,-131.16598,-141.16598,-151.16598,-161.16598,-171.16598,178.83402,168.83402,158.83402,148.83402],
|
||||
[129.09306,116.89412,105.78898,95.63017,86.23504,77.42476,69.04348,60.96591,53.09841,45.37592,37.75568,30.20867,22.70998,15.23027,7.73037,0.16098,-7.53238,-15.40109,-23.48496,-31.80703,-40.37375,-49.18062,-58.22152,-67.49946,-77.03640,-86.88079,-97.11212,-107.84156,-119.20626,-131.35191,-144.39481,-158.35719,-173.08769,171.78274,156.78187,142.43310,129.09306],
|
||||
[85.81367,77.83602,71.40003,65.88433,60.88263,56.08204,51.22755,46.12774,40.67419,34.85457,28.74909,22.50583,16.29363,10.23812,4.36029,-1.45095,-7.40778,-13.74178,-20.61213,-28.04922,-35.95530,-44.15322,-52.45486,-60.71951,-68.88732,-76.99183,-85.16746,-93.67473,-102.97950,-113.96429,-128.46293,-150.36073,175.55488,138.00554,112.28051,96.48319,85.81367],
|
||||
[48.22805,46.81921,45.24300,43.71189,42.27245,40.80022,39.00177,36.49549,32.95972,28.26545,22.54379,16.18846,9.77818,3.88971,-1.16066,-5.50500,-9.68832,-14.40052,-20.13990,-26.99385,-34.63319,-42.50584,-50.08478,-57.00760,-63.07978,-68.20773,-72.30336,-75.14845,-76.14220,-73.56875,-61.46573,-19.66028,28.39616,43.98783,48.35027,49.03265,48.22805],
|
||||
[31.42931,31.60530,31.28145,30.79047,30.38024,30.16777,29.97487,29.25597,27.27948,23.46202,17.66378,10.37176,2.68673,-4.06559,-9.01317,-12.19989,-14.47861,-17.04830,-21.00672,-26.83158,-33.98769,-41.32654,-47.85214,-52.97945,-56.36644,-57.72068,-56.62201,-52.29959,-43.64045,-30.08348,-13.41611,2.35315,14.41455,22.53506,27.54777,30.28028,31.42931],
|
||||
[22.67985,23.21169,23.25494,22.99742,22.63545,22.42369,22.46877,22.43187,21.42571,18.33186,12.46440,4.21692,-4.75068,-12.30560,-17.22721,-19.74039,-20.77499,-21.16946,-22.14607,-25.39336,-31.01102,-37.19196,-42.26227,-45.34969,-45.95366,-43.77299,-38.67388,-30.72261,-20.87969,-11.16390,-2.84711,4.17466,10.15622,15.07307,18.83144,21.33469,22.67985],
|
||||
[17.07334,17.59062,17.77934,17.69577,17.34929,16.88674,16.56217,16.38656,15.63204,12.86517,6.93562,-1.75751,-10.98436,-18.20308,-22.41588,-24.27993,-24.67590,-23.50719,-21.00605,-19.72369,-21.87960,-26.21214,-30.23195,-32.25069,-31.49417,-28.07385,-22.58093,-15.67611,-8.73630,-3.38117,0.43868,3.90117,7.49078,10.92679,13.85484,15.93237,17.07334],
|
||||
[13.37426,13.67217,13.78744,13.78998,13.54222,12.98780,12.38852,11.96065,11.09372,8.25499,2.21162,-6.34723,-14.82596,-20.89032,-23.89434,-24.45752,-23.26867,-20.14461,-15.21492,-10.62227,-9.09952,-11.18829,-14.91638,-17.58833,-17.75073,-15.65321,-12.03643,-7.38772,-2.92537,-0.15156,1.30857,3.04660,5.56513,8.30463,10.76538,12.51642,13.37426],
|
||||
[11.10969,11.11944,11.01236,10.99728,10.84097,10.32286,9.70494,9.19687,8.09157,4.94277,-1.12864,-9.05484,-16.32980,-21.04376,-22.55109,-21.19496,-17.89373,-13.44411,-8.58084,-4.24867,-1.62827,-1.86509,-4.55045,-7.42469,-8.64775,-8.12536,-6.32716,-3.48850,-0.64489,0.72027,0.97976,1.90952,4.01623,6.51266,8.80749,10.44185,11.10969],
|
||||
[9.88349,9.72040,9.41289,9.38439,9.33291,8.89921,8.31537,7.68011,6.17272,2.60695,-3.33977,-10.37899,-16.38823,-19.72660,-19.70115,-16.80477,-12.41185,-7.91607,-4.15177,-1.10381,1.22204,1.82879,0.23517,-2.13784,-3.62813,-3.94630,-3.34494,-1.85961,-0.22644,0.26762,-0.08803,0.44077,2.38763,4.89878,7.32401,9.15291,9.88349],
|
||||
[9.12464,9.18177,8.94457,9.04553,9.19618,8.89744,8.21223,7.14260,4.96349,0.86055,-4.97931,-11.14357,-15.85640,-17.78532,-16.57645,-13.08478,-8.67898,-4.59243,-1.60427,0.55144,2.39028,3.23916,2.31654,0.46434,-0.91732,-1.53003,-1.62589,-1.18564,-0.62403,-0.86624,-1.66562,-1.50145,0.21812,2.79294,5.56329,7.91823,9.12464],
|
||||
[8.06290,8.93172,9.29767,9.81684,10.30693,10.20311,9.30721,7.53634,4.41412,-0.45099,-6.41113,-11.85029,-15.25565,-15.88209,-13.96742,-10.49677,-6.46933,-2.75504,-0.08743,1.66921,3.12874,3.96903,3.45981,2.05876,0.88578,0.20951,-0.29117,-0.68669,-1.18101,-2.27487,-3.63054,-3.95562,-2.62221,-0.08793,3.01927,6.01454,8.06290],
|
||||
[6.31041,8.41617,9.93058,11.21483,12.13996,12.23034,11.14011,8.66524,4.49928,-1.34733,-7.71989,-12.71272,-15.08305,-14.75641,-12.45343,-9.09705,-5.35725,-1.83470,0.82823,2.57001,3.86519,4.69588,4.60243,3.76104,2.87601,2.13967,1.24833,0.02788,-1.62859,-3.80231,-5.90990,-6.79346,-5.87079,-3.45535,-0.15720,3.34006,6.31041],
|
||||
[4.26294,7.59975,10.43666,12.70491,14.16020,14.43398,13.18770,10.10768,4.90586,-2.08386,-9.15208,-14.09196,-15.93051,-15.08268,-12.51517,-9.09089,-5.35759,-1.77919,1.14514,3.24292,4.77489,5.90082,6.46683,6.42854,5.95440,5.04613,3.49019,1.14215,-1.96091,-5.46021,-8.43365,-9.79880,-9.13330,-6.77311,-3.34752,0.50970,4.26294],
|
||||
[2.57464,6.81988,10.72127,13.95370,16.10049,16.72460,15.39548,11.64478,5.15172,-3.36781,-11.49173,-16.72206,-18.40831,-17.31430,-14.50140,-10.79977,-6.74992,-2.76545,0.78143,3.70100,6.08013,8.07892,9.67963,10.67456,10.77058,9.65347,7.07600,3.02043,-2.09809,-7.27683,-11.16806,-12.81861,-12.13043,-9.62141,-5.97603,-1.77704,2.57464],
|
||||
[1.43503,6.27921,10.88019,14.88261,17.80063,19.02158,17.77297,13.12636,4.53718,-6.54055,-16.27050,-21.85552,-23.31365,-21.85455,-18.61101,-14.36797,-9.64057,-4.79964,-0.13239,4.18385,8.10605,11.64519,14.70734,16.97990,17.92977,16.88820,13.23164,6.81146,-1.34665,-8.97876,-14.01257,-15.81005,-14.85926,-12.00033,-7.99733,-3.40265,1.43502],
|
||||
[0.13094,5.45479,10.54962,15.08235,18.55436,20.17754,18.67574,12.20150,-0.36226,-15.49225,-26.46004,-31.19380,-31.33251,-28.66356,-24.33699,-19.03627,-13.18344,-7.06335,-0.88475,5.19490,11.05071,16.55252,21.50321,25.56424,28.16988,28.41286,24.95220,16.43585,3.63861,-8.67079,-16.18909,-18.69045,-17.68753,-14.54612,-10.18137,-5.16795,0.13094],
|
||||
[-4.14830,1.12345,5.96040,9.84415,11.94596,10.80871,4.02869,-10.36405,-27.94912,-39.79617,-44.16477,-43.57950,-40.12657,-34.99189,-28.83083,-22.02403,-14.80922,-7.34799,0.23881,7.85050,15.39197,22.75942,29.82156,36.38924,42.15868,46.59144,48.63821,46.09967,34.72041,12.13936,-8.98865,-18.65098,-20.47841,-18.40133,-14.39834,-9.45818,-4.14830],
|
||||
[-169.79948,-159.79948,-149.79948,-139.79948,-129.79948,-119.79948,-109.79948,-99.79948,-89.79948,-79.79948,-69.79948,-59.79948,-49.79948,-39.79948,-29.79948,-19.79948,-9.79948,0.20052,10.20052,20.20052,30.20052,40.20052,50.20052,60.20052,70.20052,80.20052,90.20052,100.20052,110.20052,120.20052,130.20052,140.20052,150.20052,160.20052,170.20052,-179.79948,-169.79948]
|
||||
]
|
||||
|
||||
inclination_table = [
|
||||
[-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447,-72.08447],
|
||||
[-78.33243,-77.56645,-76.64486,-75.60941,-74.49599,-73.33711,-72.16456,-71.01082,-69.90877,-68.88978,-67.98065,-67.20063,-66.55969,-66.05909,-65.69426,-65.45930,-65.35147,-65.37404,-65.53651,-65.85220,-66.33408,-66.99021,-67.82010,-68.81276,-69.94649,-71.18994,-72.50361,-73.84119,-75.15044,-76.37388,-77.45008,-78.31699,-78.91913,-79.21830,-79.20379,-78.89480,-78.33243],
|
||||
[-80.91847,-79.09801,-77.26826,-75.41050,-73.49957,-71.51974,-69.48020,-67.42760,-65.44927,-63.66181,-62.18407,-61.10090,-60.43119,-60.11709,-60.04466,-60.08935,-60.16521,-60.25535,-60.41391,-60.74312,-61.35672,-62.34264,-63.73840,-65.52698,-67.65072,-70.03207,-72.58967,-75.24472,-77.91857,-80.52353,-82.93966,-84.94483,-86.05606,-85.75384,-84.42566,-82.72116,-80.91847],
|
||||
[-77.51837,-75.51694,-73.59315,-71.68670,-69.71302,-67.57376,-65.19328,-62.57944,-59.87571,-57.36704,-55.41993,-54.35624,-54.29717,-55.07005,-56.26617,-57.42621,-58.22580,-58.56311,-58.55509,-58.48876,-58.73003,-59.58712,-61.19398,-63.49338,-66.31349,-69.46462,-72.79529,-76.19407,-79.56126,-82.77630,-85.61580,-87.26733,-86.31815,-84.15731,-81.85873,-79.63120,-77.51837],
|
||||
[-71.58980,-69.64769,-67.77321,-65.94443,-64.10554,-62.13602,-59.85758,-57.13808,-54.05141,-50.99340,-48.66453,-47.83440,-48.89447,-51.51382,-54.80435,-57.85064,-60.06631,-61.18986,-61.20437,-60.42942,-59.58264,-59.49073,-60.61581,-62.88772,-65.91135,-69.25190,-72.58760,-75.67681,-78.24048,-79.94645,-80.57004,-80.16984,-79.02581,-77.42625,-75.56790,-73.58591,-71.58980],
|
||||
[-64.35997,-62.39436,-60.44044,-58.48692,-56.55523,-54.62878,-52.55624,-50.07572,-47.03679,-43.74840,-41.19888,-40.75016,-43.15983,-47.79606,-53.17503,-58.10488,-62.07251,-64.81023,-65.90745,-65.16861,-63.23594,-61.51933,-61.25674,-62.70064,-65.25795,-68.11437,-70.67345,-72.55166,-73.47174,-73.47848,-72.95756,-72.18292,-71.16028,-69.83589,-68.20337,-66.33091,-64.35997],
|
||||
[-54.94450,-52.83610,-50.71907,-48.52548,-46.29540,-44.14811,-42.08032,-39.77454,-36.80280,-33.30065,-30.58530,-30.73124,-34.77290,-41.50404,-48.77340,-55.23978,-60.63675,-64.93033,-67.56104,-67.82610,-65.84530,-62.87774,-60.76994,-60.59320,-61.93831,-63.73453,-65.20081,-65.88752,-65.54695,-64.51690,-63.50867,-62.74044,-61.89461,-60.69909,-59.07143,-57.07765,-54.94450],
|
||||
[-42.10646,-39.67640,-37.35701,-34.97293,-32.46788,-30.02667,-27.76992,-25.30303,-22.01486,-18.09122,-15.32823,-16.39044,-22.30870,-31.32094,-40.74071,-48.83600,-55.18344,-59.91449,-62.78717,-63.30498,-61.42903,-57.98330,-54.69009,-53.10628,-53.23404,-54.07531,-54.84677,-54.97074,-54.01281,-52.44135,-51.30869,-50.77990,-50.14138,-48.93456,-47.08149,-44.68014,-42.10646],
|
||||
[-25.12461,-22.20972,-19.71770,-17.30812,-14.73074,-12.18096,-9.79096,-7.01347,-3.30221,0.76014,3.06841,1.05911,-6.08614,-16.75791,-28.16035,-37.77466,-44.50466,-48.52854,-50.32132,-50.14678,-47.98684,-44.21133,-40.39026,-38.23866,-37.87010,-38.34407,-38.95664,-39.04699,-37.96969,-36.26974,-35.35719,-35.32784,-34.98679,-33.69969,-31.46052,-28.41042,-25.12461],
|
||||
[-4.97565,-1.60199,0.92214,3.11849,5.46677,7.81249,10.07397,12.84091,16.38100,19.76510,21.12151,18.61808,11.61848,1.03273,-10.71878,-20.60587,-26.95396,-29.87498,-30.40244,-29.49437,-27.12952,-23.19291,-19.13605,-16.84996,-16.43635,-16.86796,-17.51065,-17.78722,-16.98601,-15.63402,-15.29474,-15.99460,-16.17398,-15.02255,-12.56796,-8.96345,-4.97565],
|
||||
[14.91447,18.35017,20.72172,22.57409,24.52718,26.56390,28.61333,31.02478,33.78706,36.01013,36.36989,33.79530,27.90158,19.21562,9.54519,1.38248,-3.71763,-5.61325,-5.28417,-3.97847,-1.76155,1.76478,5.44818,7.52401,7.87847,7.51982,7.00436,6.66556,7.01607,7.64759,7.26628,5.87086,4.95018,5.43404,7.43409,10.86385,14.91447],
|
||||
[31.20265,34.13364,36.24286,37.87203,39.58418,41.50443,43.52947,45.65845,47.68007,48.91359,48.52705,46.02412,41.42395,35.29504,28.85019,23.50541,20.17823,19.13590,19.80674,21.15030,22.94717,25.52415,28.20453,29.75720,30.04189,29.82318,29.56477,29.39315,29.46905,29.45564,28.53745,26.73967,25.15400,24.67305,25.61444,27.99981,31.20265],
|
||||
[43.45897,45.53118,47.31626,48.90746,50.63263,52.61803,54.74225,56.79950,58.45770,59.16957,58.40919,56.07765,52.56584,48.52949,44.70395,41.69430,39.88037,39.44508,40.12934,41.29382,42.64758,44.29218,45.93985,46.96938,47.25944,47.23840,47.23429,47.28737,47.30538,46.94314,45.73923,43.78378,41.82093,40.58525,40.46579,41.54349,43.45897],
|
||||
[53.18759,54.43224,55.88059,57.49427,59.34040,61.41406,63.57613,65.58932,67.09997,67.62703,66.81035,64.77326,62.07457,59.34036,57.01844,55.33747,54.40642,54.27684,54.81467,55.68344,56.63785,57.64137,58.61275,59.35237,59.79549,60.08844,60.36788,60.60803,60.61967,60.08419,58.75938,56.80187,54.74411,53.13609,52.31629,52.38221,53.18759],
|
||||
[62.00682,62.70613,63.84875,65.37429,67.21435,69.25270,71.31641,73.17326,74.49560,74.88083,74.10396,72.39157,70.27835,68.26326,66.64304,65.52888,64.93677,64.84030,65.14402,65.67923,66.29619,66.93920,67.60553,68.28409,68.96109,69.62909,70.24417,70.67488,70.69663,70.07359,68.73701,66.90517,64.98300,63.35731,62.27637,61.83476,62.00682],
|
||||
[70.71443,71.15184,72.02039,73.27261,74.82799,76.56362,78.31147,79.84421,80.85027,81.00173,80.21459,78.77568,77.10397,75.52742,74.23457,73.30289,72.74118,72.51798,72.57149,72.82152,73.19914,73.67611,74.26606,74.99681,75.87341,76.84434,77.77369,78.43201,78.54711,77.95236,76.72716,75.15436,73.56000,72.20185,71.23761,70.73764,70.71443],
|
||||
[79.00682,79.29184,79.87277,80.71498,81.76476,82.94241,84.12827,85.13086,85.65991,85.46559,84.62947,83.45809,82.20769,81.03569,80.03242,79.24434,78.68745,78.35646,78.23285,78.29380,78.52195,78.91276,79.47430,80.21709,81.13521,82.18169,83.23875,84.08767,84.43289,84.09671,83.21590,82.09358,80.98565,80.05465,79.39115,79.03778,79.00682],
|
||||
[86.14235,86.25121,86.50061,86.87153,87.33295,87.83175,88.26493,88.44295,88.20870,87.65877,86.96733,86.23857,85.52963,84.87675,84.30531,83.83351,83.47382,83.23411,83.11886,83.13031,83.26944,83.53626,83.92911,84.44289,85.06632,85.77827,86.54222,87.29519,87.92224,88.23116,88.09287,87.66150,87.15950,86.71170,86.37734,86.18408,86.14235],
|
||||
[88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502,88.07502]
|
||||
[-72.02070,-72.02071,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02070,-72.02071,-72.02070,-72.02071],
|
||||
[-78.23208,-77.46612,-76.54604,-75.51344,-74.40408,-73.25043,-72.08420,-70.93779,-69.84384,-68.83332,-67.93241,-67.15960,-66.52407,-66.02648,-65.66205,-65.42519,-65.31392,-65.33255,-65.49161,-65.80511,-66.28626,-66.94289,-67.77395,-68.76776,-69.90201,-71.14489,-72.45664,-73.79090,-75.09549,-76.31306,-77.38240,-78.24183,-78.83644,-79.12876,-79.10879,-78.79618,-78.23208],
|
||||
[-80.80007,-78.97830,-77.14756,-75.29021,-73.38193,-71.40769,-69.37743,-67.33857,-65.37896,-63.61481,-62.16302,-61.10460,-60.45316,-60.14557,-60.06470,-60.08698,-60.13217,-60.19219,-60.32958,-60.65151,-61.27183,-62.27481,-63.69257,-65.50302,-67.64474,-70.03800,-72.60073,-75.25455,-77.92173,-80.51496,-82.91263,-84.88736,-85.95658,-85.63251,-84.30522,-82.60297,-80.80007],
|
||||
[-77.45516,-75.43606,-73.49604,-71.57699,-69.59653,-67.45749,-65.08505,-62.48902,-59.81600,-57.35291,-55.46368,-54.46054,-54.44855,-55.23685,-56.40404,-57.49090,-58.18917,-58.42457,-58.34278,-58.24952,-58.51231,-59.42525,-61.10217,-63.46936,-66.34503,-69.53469,-72.88656,-76.29320,-79.66218,-82.88130,-85.73520,-87.38955,-86.36194,-84.15583,-81.83294,-79.58616,-77.45517],
|
||||
[-71.58214,-69.61565,-67.71488,-65.86479,-64.01505,-62.04510,-59.77482,-57.07400,-54.02405,-51.03212,-48.80491,-48.09823,-49.26412,-51.92460,-55.16562,-58.07793,-60.10267,-61.01513,-60.84749,-59.97822,-59.15799,-59.18575,-60.45940,-62.86069,-65.97595,-69.36736,-72.71868,-75.80268,-78.35851,-80.06262,-80.67983,-80.25871,-79.08901,-77.46953,-75.59576,-73.59787,-71.58215],
|
||||
[-64.39807,-62.40221,-60.40960,-58.42549,-56.48151,-54.55795,-52.49863,-50.03954,-47.03044,-43.80319,-41.39118,-41.16169,-43.78688,-48.51954,-53.83971,-58.60413,-62.35170,-64.81766,-65.60605,-64.62579,-62.64650,-61.08659,-61.05364,-62.68316,-65.34905,-68.24163,-70.78236,-72.62117,-73.51797,-73.52965,-73.02048,-72.24528,-71.21594,-69.88980,-68.25886,-66.38361,-64.39807],
|
||||
[-55.02826,-52.87120,-50.69073,-48.44731,-46.19513,-44.04849,-42.00465,-39.74123,-36.79801,-33.33110,-30.77621,-31.26765,-35.68330,-42.58861,-49.78570,-56.05256,-61.22645,-65.24992,-67.52021,-67.43115,-65.26549,-62.35447,-60.45735,-60.49007,-61.96843,-63.81210,-65.26064,-65.90429,-65.53604,-64.51130,-63.52424,-62.77292,-61.94296,-60.76846,-59.16172,-57.17787,-55.02826],
|
||||
[-42.23934,-39.72248,-37.30606,-34.84704,-32.29950,-29.84715,-27.62882,-25.25073,-22.02346,-18.13398,-15.56621,-17.09131,-23.52381,-32.78684,-42.11183,-49.91489,-55.93881,-60.34177,-62.85919,-63.04596,-60.93631,-57.41244,-54.21948,-52.82417,-53.10885,-54.02972,-54.81946,-54.92826,-53.94911,-52.38029,-51.27875,-50.79557,-50.20937,-49.05107,-47.23568,-44.84941,-42.23934],
|
||||
[-25.31616,-22.26353,-19.64432,-17.13765,-14.48794,-11.90452,-9.56551,-6.93532,-3.35246,0.62534,2.69744,0.20162,-7.49683,-18.49333,-29.80260,-38.99555,-45.22087,-48.81124,-50.28975,-49.88122,-47.49942,-43.57896,-39.80201,-37.81589,-37.58213,-38.12733,-38.79073,-38.91636,-37.84560,-36.15384,-35.28930,-35.35164,-35.11620,-33.90633,-31.71407,-28.67497,-25.31616],
|
||||
[-5.22365,-1.68002,0.98130,3.28459,5.73141,8.13291,10.33797,12.92226,16.28019,19.52644,20.64919,17.75076,10.26968,-0.68527,-12.39654,-21.81573,-27.55757,-29.98547,-30.24089,-29.18412,-26.62224,-22.51726,-18.50023,-16.36665,-16.02599,-16.47452,-17.18522,-17.56335,-16.82114,-15.49276,-15.21405,-16.04947,-16.38744,-15.33409,-12.92178,-9.31548,-5.22365],
|
||||
[14.65727,18.24457,20.73560,22.68750,24.74090,26.83478,28.82717,31.06453,33.64927,35.73650,35.91607,33.06931,26.82267,17.82545,8.14938,0.35249,-4.22224,-5.65846,-5.08244,-3.67265,-1.30171,2.36894,6.00997,7.96495,8.31670,8.01335,7.45026,6.96852,7.19717,7.76654,7.31456,5.77666,4.68883,5.07867,7.05547,10.50432,14.65727],
|
||||
[31.00203,34.03206,36.22486,37.93041,39.71929,41.67672,43.64451,45.63057,47.51149,48.64179,48.13476,45.46014,40.64785,34.34474,27.90343,22.77471,19.78522,19.08118,19.96093,21.39191,23.28877,25.96005,28.61507,30.09860,30.42073,30.29938,30.04062,29.74069,29.65970,29.53545,28.53162,26.62276,24.91817,24.37385,25.31100,27.72542,31.00203],
|
||||
[43.33608,45.45851,47.28808,48.92364,50.69187,52.68920,54.75852,56.70372,58.24993,58.87748,58.03709,55.61656,52.01961,47.93440,44.13769,41.24459,39.61639,39.39065,40.22833,41.47069,42.89022,44.59331,46.23881,47.24171,47.57154,47.63935,47.66249,47.62919,47.50096,47.00810,45.71114,43.68014,41.65440,40.38784,40.27252,41.37670,43.33608],
|
||||
[53.10131,54.36161,55.82606,57.45873,59.32146,61.39014,63.50628,65.43734,66.85905,67.31408,66.44780,64.38450,61.68268,58.96721,56.68844,55.08044,54.25566,54.24982,54.89128,55.82780,56.83438,57.87845,58.85920,59.59271,60.06042,60.40887,60.71534,60.90716,60.81057,60.15911,58.74748,56.73559,54.64618,53.02448,52.20550,52.28132,53.10131],
|
||||
[61.90363,62.59082,63.73000,65.25974,67.10373,69.13404,71.16923,72.97878,74.24745,74.58969,73.79370,72.08739,69.99806,68.01780,66.44167,65.38391,64.86230,64.84287,65.21557,65.80372,66.46017,67.12970,67.80720,68.49179,69.18909,69.89166,70.52514,70.92481,70.86509,70.14456,68.73300,66.86155,64.92449,63.29260,62.20331,61.74779,61.90363],
|
||||
[70.57319,70.97549,71.81891,73.05700,74.60513,76.33503,78.07584,79.60158,80.60606,80.76720,79.99878,78.58008,76.92858,75.37566,74.11340,73.22087,72.70518,72.52979,72.62677,72.91213,73.31657,73.81370,74.42101,75.17239,76.07666,77.07532,78.01176,78.63384,78.66938,77.98598,76.70086,75.10445,73.50638,72.14451,71.16426,70.63412,70.57319],
|
||||
[78.82351,79.06440,79.60559,80.41612,81.44382,82.60991,83.79747,84.82323,85.41014,85.29919,84.52961,83.39228,82.15604,80.99185,79.99787,79.22370,78.68527,78.37555,78.27394,78.35635,78.60546,79.01788,79.60326,80.37283,81.31875,82.38760,83.44917,84.26774,84.54142,84.12292,83.18704,82.03917,80.91872,79.97342,79.28584,78.89722,78.82351],
|
||||
[85.92404,85.99807,86.21370,86.55320,86.98729,87.46743,87.90712,88.15645,88.05609,87.61718,86.98684,86.28678,85.58976,84.94098,84.37090,83.90045,83.54357,83.30879,83.20077,83.22179,83.37274,83.65354,84.06234,84.59369,85.23581,85.96691,86.74942,87.51716,88.14109,88.39226,88.15089,87.63861,87.08412,86.59723,86.22810,86.00055,85.92404],
|
||||
[88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420,88.21420]
|
||||
]
|
||||
|
||||
intensity_table = [
|
||||
[0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677,0.54677],
|
||||
[0.60733,0.60103,0.59321,0.58408,0.57385,0.56274,0.55099,0.53886,0.52664,0.51464,0.50318,0.49258,0.48311,0.47506,0.46864,0.46409,0.46158,0.46131,0.46341,0.46797,0.47499,0.48434,0.49579,0.50895,0.52332,0.53833,0.55334,0.56771,0.58086,0.59227,0.60156,0.60848,0.61292,0.61488,0.61448,0.61189,0.60733],
|
||||
[0.63154,0.61845,0.60363,0.58729,0.56950,0.55031,0.52986,0.50843,0.48660,0.46508,0.44473,0.42628,0.41025,0.39690,0.38632,0.37857,0.37385,0.37260,0.37540,0.38291,0.39557,0.41347,0.43621,0.46292,0.49236,0.52306,0.55344,0.58192,0.60704,0.62760,0.64283,0.65244,0.65659,0.65582,0.65087,0.64254,0.63154],
|
||||
[0.62000,0.60125,0.58151,0.56085,0.53899,0.51544,0.48977,0.46196,0.43279,0.40379,0.37690,0.35385,0.33554,0.32180,0.31173,0.30436,0.29937,0.29738,0.29983,0.30853,0.32501,0.34983,0.38230,0.42070,0.46273,0.50598,0.54808,0.58665,0.61944,0.64465,0.66128,0.66932,0.66957,0.66335,0.65211,0.63725,0.62000],
|
||||
[0.58540,0.56274,0.53995,0.51720,0.49410,0.46971,0.44278,0.41255,0.37961,0.34621,0.31570,0.29135,0.27491,0.26562,0.26073,0.25737,0.25418,0.25173,0.25221,0.25901,0.27564,0.30394,0.34296,0.38959,0.43988,0.49027,0.53788,0.58008,0.61437,0.63888,0.65302,0.65739,0.65335,0.64259,0.62670,0.60715,0.58540],
|
||||
[0.53990,0.51548,0.49130,0.46766,0.44447,0.42102,0.39585,0.36752,0.33593,0.30307,0.27292,0.25027,0.23814,0.23543,0.23760,0.24017,0.24116,0.24059,0.23977,0.24231,0.25416,0.28019,0.32067,0.37126,0.42556,0.47801,0.52510,0.56440,0.59381,0.61260,0.62170,0.62236,0.61571,0.60295,0.58524,0.56369,0.53990],
|
||||
[0.48818,0.46438,0.44084,0.41767,0.39521,0.37350,0.35178,0.32863,0.30295,0.27543,0.24958,0.23085,0.22313,0.22534,0.23244,0.24016,0.24725,0.25311,0.25619,0.25738,0.26278,0.28057,0.31495,0.36280,0.41574,0.46566,0.50804,0.54032,0.56070,0.57052,0.57345,0.57128,0.56367,0.55075,0.53312,0.51166,0.48818],
|
||||
[0.43218,0.41124,0.39069,0.37048,0.35104,0.33291,0.31620,0.29993,0.28232,0.26276,0.24367,0.22976,0.22479,0.22857,0.23760,0.24889,0.26192,0.27556,0.28577,0.28998,0.29174,0.29954,0.32156,0.35867,0.40314,0.44569,0.48090,0.50518,0.51615,0.51692,0.51415,0.50994,0.50209,0.48968,0.47316,0.45335,0.43218],
|
||||
[0.37898,0.36321,0.34812,0.33368,0.32029,0.30839,0.29830,0.28945,0.28010,0.26891,0.25668,0.24625,0.24088,0.24246,0.25067,0.26352,0.27927,0.29594,0.30956,0.31664,0.31798,0.31969,0.33051,0.35422,0.38581,0.41752,0.44408,0.46107,0.46532,0.46038,0.45387,0.44781,0.43921,0.42706,0.41219,0.39562,0.37898],
|
||||
[0.34141,0.33249,0.32432,0.31714,0.31161,0.30779,0.30545,0.30409,0.30213,0.29754,0.28963,0.27981,0.27109,0.26711,0.27059,0.28075,0.29432,0.30838,0.32039,0.32820,0.33136,0.33312,0.33973,0.35435,0.37434,0.39514,0.41304,0.42408,0.42536,0.41914,0.41071,0.40169,0.39062,0.37761,0.36424,0.35187,0.34141],
|
||||
[0.32867,0.32594,0.32420,0.32395,0.32630,0.33102,0.33698,0.34292,0.34678,0.34593,0.33903,0.32732,0.31415,0.30395,0.30057,0.30442,0.31263,0.32253,0.33245,0.34086,0.34708,0.35294,0.36127,0.37252,0.38535,0.39852,0.41027,0.41774,0.41871,0.41327,0.40286,0.38883,0.37279,0.35689,0.34336,0.33390,0.32867],
|
||||
[0.34041,0.34097,0.34394,0.34953,0.35870,0.37101,0.38453,0.39684,0.40514,0.40637,0.39894,0.38449,0.36738,0.35274,0.34431,0.34264,0.34599,0.35295,0.36228,0.37184,0.38062,0.38995,0.40068,0.41156,0.42185,0.43217,0.44201,0.44914,0.45121,0.44627,0.43315,0.41330,0.39087,0.37008,0.35387,0.34401,0.34041],
|
||||
[0.37313,0.37420,0.38001,0.39014,0.40446,0.42181,0.43988,0.45594,0.46693,0.46961,0.46214,0.44621,0.42680,0.40959,0.39817,0.39301,0.39304,0.39763,0.40583,0.41537,0.42477,0.43480,0.44612,0.45788,0.46954,0.48141,0.49294,0.50198,0.50563,0.50085,0.48580,0.46223,0.43524,0.41014,0.39049,0.37812,0.37313],
|
||||
[0.42356,0.42408,0.43096,0.44342,0.46009,0.47887,0.49731,0.51304,0.52358,0.52620,0.51923,0.50394,0.48467,0.46656,0.45306,0.44501,0.44198,0.44352,0.44889,0.45639,0.46470,0.47409,0.48543,0.49886,0.51385,0.52947,0.54409,0.55526,0.56003,0.55559,0.54075,0.51743,0.49032,0.46455,0.44383,0.43002,0.42356],
|
||||
[0.48455,0.48475,0.49083,0.50202,0.51666,0.53249,0.54719,0.55888,0.56585,0.56650,0.55991,0.54692,0.53031,0.51359,0.49951,0.48937,0.48348,0.48174,0.48371,0.48850,0.49531,0.50420,0.51581,0.53051,0.54771,0.56575,0.58223,0.59442,0.59970,0.59626,0.58388,0.56455,0.54198,0.52029,0.50258,0.49049,0.48455],
|
||||
[0.54041,0.54034,0.54396,0.55064,0.55927,0.56837,0.57642,0.58216,0.58460,0.58302,0.57718,0.56756,0.55545,0.54258,0.53062,0.52078,0.51381,0.51011,0.50972,0.51240,0.51793,0.52626,0.53755,0.55170,0.56796,0.58472,0.59979,0.61087,0.61607,0.61448,0.60648,0.59374,0.57883,0.56443,0.55261,0.54449,0.54041],
|
||||
[0.57307,0.57207,0.57258,0.57422,0.57649,0.57880,0.58055,0.58121,0.58037,0.57778,0.57340,0.56742,0.56031,0.55268,0.54526,0.53876,0.53378,0.53081,0.53014,0.53192,0.53617,0.54284,0.55170,0.56233,0.57398,0.58557,0.59583,0.60355,0.60784,0.60838,0.60548,0.60000,0.59319,0.58628,0.58027,0.57579,0.57307],
|
||||
[0.57801,0.57662,0.57545,0.57444,0.57349,0.57249,0.57133,0.56991,0.56816,0.56605,0.56360,0.56089,0.55803,0.55520,0.55261,0.55047,0.54900,0.54836,0.54871,0.55012,0.55257,0.55599,0.56021,0.56498,0.56997,0.57483,0.57918,0.58272,0.58521,0.58659,0.58688,0.58625,0.58495,0.58326,0.58141,0.57962,0.57801],
|
||||
[0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612,0.56612]
|
||||
[0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507,0.54507],
|
||||
[0.60562,0.59923,0.59133,0.58213,0.57184,0.56070,0.54892,0.53679,0.52458,0.51262,0.50121,0.49067,0.48128,0.47330,0.46697,0.46249,0.46006,0.45986,0.46203,0.46665,0.47372,0.48312,0.49460,0.50778,0.52217,0.53717,0.55217,0.56652,0.57964,0.59102,0.60027,0.60715,0.61152,0.61342,0.61294,0.61026,0.60562],
|
||||
[0.62993,0.61663,0.60163,0.58513,0.56721,0.54792,0.52741,0.50597,0.48417,0.46274,0.44252,0.42424,0.40840,0.39524,0.38483,0.37722,0.37262,0.37149,0.37444,0.38211,0.39496,0.41303,0.43591,0.46271,0.49220,0.52288,0.55321,0.58160,0.60660,0.62705,0.64217,0.65166,0.65569,0.65477,0.64966,0.64113,0.62993],
|
||||
[0.61859,0.59954,0.57951,0.55859,0.53652,0.51281,0.48703,0.45921,0.43010,0.40125,0.37460,0.35184,0.33383,0.32034,0.31043,0.30313,0.29816,0.29624,0.29887,0.30789,0.32478,0.35003,0.38290,0.42162,0.46385,0.50716,0.54918,0.58755,0.62009,0.64502,0.66138,0.66918,0.66921,0.66276,0.65127,0.63614,0.61859],
|
||||
[0.58434,0.56134,0.53820,0.51511,0.49174,0.46715,0.44010,0.40984,0.37699,0.34382,0.31364,0.28967,0.27359,0.26453,0.25966,0.25610,0.25262,0.24997,0.25053,0.25779,0.27518,0.30435,0.34417,0.39141,0.44206,0.49253,0.54000,0.58194,0.61593,0.64015,0.65395,0.65794,0.65353,0.64245,0.62626,0.60641,0.58434],
|
||||
[0.53921,0.51448,0.48995,0.46595,0.44250,0.41888,0.39359,0.36521,0.33366,0.30097,0.27115,0.24895,0.23726,0.23477,0.23677,0.23885,0.23920,0.23803,0.23691,0.23986,0.25296,0.28060,0.32245,0.37391,0.42855,0.48085,0.52753,0.56643,0.59562,0.61429,0.62316,0.62341,0.61626,0.60311,0.58508,0.56327,0.53921],
|
||||
[0.48785,0.46379,0.43988,0.41636,0.39367,0.37182,0.34998,0.32674,0.30099,0.27346,0.24780,0.22959,0.22251,0.22507,0.23198,0.23916,0.24558,0.25057,0.25278,0.25389,0.26060,0.28058,0.31692,0.36595,0.41928,0.46891,0.51065,0.54231,0.56238,0.57214,0.57493,0.57236,0.56426,0.55095,0.53309,0.51149,0.48785],
|
||||
[0.43209,0.41089,0.38995,0.36941,0.34979,0.33155,0.31470,0.29826,0.28044,0.26067,0.24164,0.22828,0.22418,0.22862,0.23770,0.24867,0.26122,0.27397,0.28296,0.28650,0.28895,0.29863,0.32271,0.36133,0.40653,0.44908,0.48374,0.50731,0.51774,0.51826,0.51530,0.51075,0.50252,0.48985,0.47321,0.45336,0.43209],
|
||||
[0.37890,0.36283,0.34739,0.33271,0.31922,0.30724,0.29696,0.28780,0.27809,0.26658,0.25432,0.24439,0.23994,0.24247,0.25117,0.26398,0.27930,0.29517,0.30771,0.31403,0.31546,0.31823,0.33068,0.35590,0.38846,0.42051,0.44683,0.46322,0.46680,0.46142,0.45465,0.44832,0.43950,0.42721,0.41228,0.39568,0.37890],
|
||||
[0.34114,0.33192,0.32348,0.31616,0.31061,0.30672,0.30410,0.30225,0.29980,0.29492,0.28700,0.27755,0.26956,0.26653,0.27083,0.28123,0.29446,0.30791,0.31935,0.32678,0.32987,0.33216,0.33985,0.35562,0.37648,0.39779,0.41572,0.42632,0.42691,0.42012,0.41134,0.40209,0.39087,0.37775,0.36429,0.35181,0.34114],
|
||||
[0.32818,0.32516,0.32319,0.32283,0.32517,0.32980,0.33535,0.34062,0.34397,0.34296,0.33615,0.32475,0.31211,0.30265,0.30010,0.30443,0.31265,0.32241,0.33228,0.34067,0.34700,0.35327,0.36224,0.37416,0.38773,0.40158,0.41356,0.42060,0.42076,0.41455,0.40362,0.38928,0.37303,0.35700,0.34334,0.33369,0.32818],
|
||||
[0.33981,0.34000,0.34266,0.34809,0.35721,0.36937,0.38240,0.39400,0.40180,0.40293,0.39568,0.38157,0.36502,0.35110,0.34343,0.34233,0.34605,0.35337,0.36304,0.37282,0.38187,0.39163,0.40273,0.41394,0.42487,0.43601,0.44625,0.45294,0.45399,0.44803,0.43420,0.41393,0.39124,0.37028,0.35389,0.34377,0.33981],
|
||||
[0.37236,0.37289,0.37826,0.38816,0.40237,0.41956,0.43724,0.45274,0.46333,0.46592,0.45864,0.44316,0.42447,0.40808,0.39741,0.39283,0.39339,0.39860,0.40735,0.41725,0.42701,0.43745,0.44902,0.46095,0.47308,0.48570,0.49764,0.50631,0.50895,0.50305,0.48719,0.46316,0.43591,0.41060,0.39068,0.37789,0.37236],
|
||||
[0.42245,0.42215,0.42846,0.44064,0.45724,0.47601,0.49435,0.50993,0.52038,0.52304,0.51631,0.50148,0.48288,0.46550,0.45264,0.44515,0.44269,0.44488,0.45083,0.45875,0.46742,0.47714,0.48867,0.50225,0.51759,0.53373,0.54863,0.55948,0.56339,0.55795,0.54232,0.51859,0.49131,0.46537,0.44426,0.42977,0.42245],
|
||||
[0.48319,0.48226,0.48758,0.49842,0.51308,0.52913,0.54416,0.55622,0.56358,0.56459,0.55836,0.54575,0.52954,0.51323,0.49956,0.48985,0.48445,0.48324,0.48569,0.49085,0.49796,0.50710,0.51894,0.53390,0.55144,0.56981,0.58634,0.59810,0.60259,0.59827,0.58527,0.56571,0.54318,0.52144,0.50331,0.49032,0.48319],
|
||||
[0.53929,0.53799,0.54070,0.54691,0.55552,0.56497,0.57363,0.58010,0.58328,0.58236,0.57702,0.56775,0.55586,0.54317,0.53137,0.52173,0.51505,0.51167,0.51159,0.51458,0.52039,0.52900,0.54059,0.55506,0.57159,0.58845,0.60334,0.61392,0.61846,0.61626,0.60790,0.59512,0.58032,0.56589,0.55363,0.54459,0.53929],
|
||||
[0.57278,0.57090,0.57068,0.57187,0.57403,0.57656,0.57878,0.58007,0.57991,0.57795,0.57409,0.56849,0.56162,0.55414,0.54681,0.54040,0.53554,0.53271,0.53223,0.53423,0.53873,0.54564,0.55475,0.56559,0.57735,0.58891,0.59900,0.60643,0.61040,0.61066,0.60758,0.60203,0.59514,0.58801,0.58156,0.57637,0.57278],
|
||||
[0.57900,0.57728,0.57584,0.57463,0.57360,0.57263,0.57160,0.57039,0.56890,0.56707,0.56489,0.56241,0.55976,0.55710,0.55465,0.55263,0.55127,0.55074,0.55121,0.55273,0.55530,0.55883,0.56314,0.56798,0.57300,0.57785,0.58216,0.58562,0.58802,0.58928,0.58943,0.58865,0.58716,0.58523,0.58309,0.58097,0.57900],
|
||||
[0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830,0.56830]
|
||||
]
|
||||
|
||||
|
||||
|
||||
@@ -356,6 +356,10 @@ class mavfile(object):
|
||||
mavlink.MAV_TYPE_ADSB,
|
||||
mavlink.MAV_TYPE_ONBOARD_CONTROLLER):
|
||||
return False
|
||||
if msg.autopilot in frozenset([
|
||||
mavlink.MAV_AUTOPILOT_INVALID
|
||||
]):
|
||||
return False
|
||||
return True
|
||||
|
||||
def post_message(self, msg):
|
||||
@@ -791,16 +795,20 @@ class mavfile(object):
|
||||
MAV_ACTION_CALIBRATE_PRESSURE = 20
|
||||
self.mav.action_send(self.target_system, self.target_component, MAV_ACTION_CALIBRATE_PRESSURE)
|
||||
|
||||
def reboot_autopilot(self, hold_in_bootloader=False):
|
||||
def reboot_autopilot(self, hold_in_bootloader=False, force=False):
|
||||
'''reboot the autopilot'''
|
||||
if self.mavlink10():
|
||||
if hold_in_bootloader:
|
||||
param1 = 3
|
||||
else:
|
||||
param1 = 1
|
||||
if force:
|
||||
param6 = 20190226
|
||||
else:
|
||||
param6 = 0
|
||||
self.mav.command_long_send(self.target_system, self.target_component,
|
||||
mavlink.MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 0,
|
||||
param1, 0, 0, 0, 0, 0, 0)
|
||||
param1, 0, 0, 0, 0, param6, 0)
|
||||
|
||||
def wait_gps_fix(self):
|
||||
self.recv_match(type='VFR_HUD', blocking=True)
|
||||
@@ -920,7 +928,7 @@ class mavfile(object):
|
||||
self.mav.signing.timestamp = 0
|
||||
|
||||
def set_close_on_exec(fd):
|
||||
'''set the clone on exec flag on a file descriptor. Ignore exceptions'''
|
||||
'''set the close on exec flag on a file descriptor. Ignore exceptions'''
|
||||
try:
|
||||
import fcntl
|
||||
flags = fcntl.fcntl(fd, fcntl.F_GETFD)
|
||||
@@ -1321,6 +1329,8 @@ class mavtcpin(mavfile):
|
||||
self.port = None
|
||||
|
||||
def close(self):
|
||||
if self.port is not None:
|
||||
self.port.close()
|
||||
self.listen.close()
|
||||
|
||||
def recv(self,n=None):
|
||||
|
||||
@@ -38,12 +38,6 @@ fi
|
||||
|
||||
test -z "$MDEF" && MDEF="../message_definitions"
|
||||
|
||||
# delete the pretests file if more than 1 minute old, this prevents the 'npm test' call near the end having to re-do the pretests
|
||||
if [ "`find pretests.done.swp -mmin +5 2>/dev/null`" ]; then
|
||||
rm pretests.done.swp
|
||||
fi
|
||||
|
||||
if [[ ! -f "pretests.done.swp" ]]; then
|
||||
|
||||
# build js bindings we want to test
|
||||
printf "${RED}Generating JS-NextGen bindings to test...${NC}\n\n"
|
||||
@@ -75,20 +69,9 @@ if [[ ! -f "pretests.done.swp" ]]; then
|
||||
cd ../..
|
||||
|
||||
printf "${RED}JS-NextGen PRETEST setup done.${NC}\n\n"
|
||||
touch pretests.done.swp
|
||||
|
||||
|
||||
else
|
||||
|
||||
printf "${RED}JS-NextGen PRETEST setup already recently done, skipping.${NC}\n\n"
|
||||
|
||||
fi
|
||||
|
||||
# 'npm test' sets this env var , so this stops it becoming a recursive call.
|
||||
if [[ ! -z "${npm_package_scripts_pretest}" ]]; then
|
||||
# stop here if we are in pre-test
|
||||
exit 0
|
||||
fi
|
||||
|
||||
# run the automatically generated tool for build/pack, ie create and pack one of everything, no byte-level checking of the packed results tho, comes later.
|
||||
printf "${RED}Running non-NPM JS-NextGen create/pack tests ...${NC}\n\n"
|
||||
@@ -111,15 +94,14 @@ make testmav1.0_common testmav2.0_common testmav1.0_ardupilotmega testmav2.0_ard
|
||||
popd > $OUT2
|
||||
|
||||
|
||||
# make big collection ~990 of mocha tests based on C output like the above but more thorough, this includes byte-level checking of the packed results
|
||||
# run the ~990 or more mocha tests we just made:
|
||||
# we also have a big collection ~990 of mocha tests based on C output like the above but more thorough, this includes byte-level
|
||||
# checking of the packed results etc.
|
||||
# u can/should also run the ~990 or more mocha tests we just made:
|
||||
#( this uses generator/javascript/package.json -> runs make_tests.py -> outputs made_tests.js -> which are then executed by 'mocha test' )
|
||||
printf "\n${RED}Running automated JS-NextGen NPM test suite...${NC}\n\n"
|
||||
sleep 1
|
||||
cd generator/javascript
|
||||
|
||||
npm test 2>/dev/null > $OUT0
|
||||
cd ../..
|
||||
echo "tip: if not bring auto-run as a auto-test, u can run the next-stage of tests with mocha here:"
|
||||
echo "cd generator/javascript"
|
||||
echo "npm test"
|
||||
echo "cd -"
|
||||
|
||||
|
||||
printf "\n${RED}JS-NextGen Testing done.${NC}\n\n"
|
||||
|
||||
@@ -23,7 +23,7 @@ from argparse import ArgumentParser
|
||||
parser = ArgumentParser(description=__doc__)
|
||||
parser.add_argument("--plot", action='store_true', default=False, help="plot errors")
|
||||
parser.add_argument("--minspeed", type=float, default=6, help="minimum speed")
|
||||
parser.add_argument("--gps", default='', help="GPS number")
|
||||
parser.add_argument("--gps", type=int, default=0, help="GPS number")
|
||||
parser.add_argument("logs", metavar="LOG", nargs="+")
|
||||
|
||||
args = parser.parse_args()
|
||||
@@ -83,13 +83,17 @@ def gps_lag(logfile):
|
||||
dtcount = 0
|
||||
|
||||
while True:
|
||||
m = mlog.recv_match(type=['GPS'+args.gps,'IMU','ATT','GPA'+args.gps])
|
||||
m = mlog.recv_match(type=['GPS','IMU','ATT','GPA'])
|
||||
if m is None:
|
||||
break
|
||||
t = m.get_type()
|
||||
if t.startswith('GPS') and m.Status >= 3 and m.Spd>args.minspeed:
|
||||
if m.I != args.gps:
|
||||
continue
|
||||
GPS = m;
|
||||
elif t.startswith('GPA') and GPS is not None and GPS.TimeUS == m.TimeUS:
|
||||
if m.I != args.gps:
|
||||
continue
|
||||
v = Vector3(GPS.Spd*cos(radians(GPS.GCrs)), GPS.Spd*sin(radians(GPS.GCrs)), GPS.VZ)
|
||||
vel.append(v)
|
||||
timestamps.append(m.SMS*0.001)
|
||||
@@ -97,6 +101,8 @@ def gps_lag(logfile):
|
||||
elif t == 'ATT':
|
||||
ATT = m
|
||||
elif t == 'IMU':
|
||||
if m.I != 0:
|
||||
continue
|
||||
if ATT is not None:
|
||||
ga = earth_accel_df(m, ATT)
|
||||
ga.z += 9.80665
|
||||
|
||||
@@ -65,7 +65,8 @@ test_node() {
|
||||
ln -sf /usr/bin/nodejs ~/bin/node
|
||||
. ~/.bashrc
|
||||
fi
|
||||
cd "$SRC_DIR/pymavlink/generator/javascript" && npm test
|
||||
(cd "$SRC_DIR/pymavlink/generator/javascript" && npm install)
|
||||
(cd "$SRC_DIR/pymavlink/generator/javascript" && npm test)
|
||||
}
|
||||
|
||||
if [ "$#" -eq 1 ]; then
|
||||
|
||||
Reference in New Issue
Block a user